Skip to content

Conversation

@ivonaj
Copy link
Collaborator

@ivonaj ivonaj commented Sep 25, 2018

Read karto mapper object, manipulate the position of each submap via interactive marker, according to the transformation performed on each submap, refresh associated pose graphs and merge them together

karto::Dataset* dataset_;
// TF
tf::TransformBroadcaster* tfB_;
tf::TransformListener tf_;
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I dont see anything that uses this, please remove

interactive_markers::InteractiveMarkerServer* interactive_server_;
std::map<int, Eigen::Vector3d> submap_locations_;
std::vector<karto::LocalizedRangeScanVector> scans_vec;
std::map<int, tf::Transform> tf_map;
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

what is tf_map?

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

saves transform that should be applied to the original pose graphs to correct them according to the marker

Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

please rename to something more immediately clear

/*****************************************************************************/
MergeMapTool::MergeMapTool() : interactive_server_(NULL)
MergeMapTool::MergeMapTool() : interactive_server_(NULL),
tf_(ros::Duration(14400.))// 4 hours
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

4 hours is alot, though I dont think you need tf_ anymore

resolution_ = 0.05;
}

karto::LaserRangeFinder* laser =
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Are the parameters on this correct? I think in slam_toolbox crease the laser and then change all the default parameters from the just karto-custom thing

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes, true, this sets the default parameters that should be overwritten after obtaining a laser scan

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

karto::dataset is a separate class and isn't within the karto::mapper.I am working on serialization of that object as well to assign laser the correct custom data. Except for that change, this part is good to be merged :)

bbox_min_tf.setRotation(tf::createQuaternionFromRPY(0, 0, 0));
tf::Transform bbox_min_tf_corr;
bbox_min_tf_corr = submap_correction*bbox_min_tf;//*
auto bbox_min_corr = karto::Vector2<kt_double>(bbox_min_tf_corr.getOrigin().x(),bbox_min_tf_corr.getOrigin().y());
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

remove all autos for correct type

tf::Transform submap_correction = tf_map[id];

//TRANSFORM BARYCENTERR POSE
karto::Pose2 baryCenter_pose = pScan_copy->GetBarycenterPose();
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

const

tf::Transform baryCenterPose_corr;
baryCenterPose_corr = submap_correction*baryCenter_pose_tf;//*

karto::Pose2 karto_baryCenterPose_corr = \
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

const karto::Pose2 karto_baryCenterPose_corr(args) use the constructor, you're incurring an extra copy. Please do for all instances below


// TRANSFORM UNFILTERED POINTS USED
karto::PointVectorDouble UPR_vec = pScan_copy->GetPointReadings();
for(auto it_upr = UPR_vec.begin(); it_upr!=UPR_vec.end();it_upr++)
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

++it_upr

pScan_copy->SetOdometricPose(karto_robotPose_odom);

transformed_scans.push_back(pScan_copy);

Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this entire chunk is way way too long. You need to break this out into multiple functions, its alot of the same boiler plate over and over again

return karto::Pose2(pose_corr.getOrigin().x(), pose_corr.getOrigin().y(), tf::getYaw(pose_corr.getRotation()));
}

karto::Vector2<kt_double>ApplyCorrection(karto::Vector2<kt_double > pose, tf::Transform& submap_correction)
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

space

//
// return T(pose_corr.getOrigin().x(), pose_corr.getOrigin().y(), tf::getYaw(pose_corr.getRotation()));
// }
karto::Pose2 ApplyCorrection(karto::Pose2 pose, tf::Transform& submap_correction)
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

return reference and make all inputs references and const when appropriate in both


karto::Vector2<kt_double>ApplyCorrection(karto::Vector2<kt_double > pose, tf::Transform& submap_correction)
{
tf::Transform pose_tf;
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

tf::Transform pose_tf, pose_cor;

interactive_markers::InteractiveMarkerServer* interactive_server_;
std::map<int, Eigen::Vector3d> submap_locations_;
std::vector<karto::LocalizedRangeScanVector> scans_vec;
std::map<int, tf::Transform> submaps_correction_tf;
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

submaps_correction_tf -> submap_marker_transform_

Also add underscore to scans_vec_

karto::LocalizedRangeScanVector scans = mapper->GetAllProcessedScans(); // TODO should I be saving a vect or of these mapper objects? / scans, A: YES

// num_submaps_++ and name frame appropriately
mapper_ = new karto::Mapper();
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this shouldnt be a class variable -- delete pointer at end of function or when you're done with it

int_marker.pose.position.x = m.pose.position.x;
int_marker.pose.position.y = m.pose.position.y;
int_marker.scale = 0.6;
int_marker.scale = 2;
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

2.4

// publish it for visualization/map_saver using sstMS_[0]'s for meta and normal'

// later, take nodes in graph mutually closest to each other and scana match
// take nodes in graph mutually closest to each other and scan match
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

delete all these comments

mat.getRPY(roll, pitch, yaw);
tf::Vector3 old_submap_loc(submap_locations_[id](0),submap_locations_[id](1), 0.);
tf::Transform previous_submap_correction = submaps_correction_tf[id];
previous_submap_correction.setOrigin(old_submap_loc);
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

previous_submap_correction.setOrigin(tf::Vector3(submap_locations_id,submap_locations_id, 0.)));

tfB_->sendTransform(tf::StampedTransform (new_submap_location,
ros::Time::now(), "/map", "/map_"+std::to_string(id)));

submaps_correction_tf[id]*=previous_submap_correction.inverse()*new_submap_location;
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

write full line out

interactive_server_->insert(int_marker, \
boost::bind(&MergeMapTool::ProcessInteractiveFeedback, this, _1));
interactive_server_->applyChanges();
if (mapper)
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

No if, delete and then set to NULL like you should do with all pointers

karto::LocalizedRangeScan* pScan;
karto::LocalizedRangeScanVector transformed_scans;
std::vector<karto::LocalizedRangeScanVector> vector_of_scans = scans_vec;
std::vector<karto::LocalizedRangeScanVector> vector_of_scans = scans_vec_;
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Make this a reference


/*****************************************************************************/
void MergeMapTool::KartoToROSOccupancyGrid( \
nav_msgs::GetMap::Response MergeMapTool::KartoToROSOccupancyGrid( \
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

return ref?

{
ROS_INFO("MergeMapTool: Could not make Karto occupancy grid.");
return map;
return;
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

memory leak!

~MergeMapTool();

private:
typedef std::unique_ptr<karto::Pose2> Pose2_ptr;
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

why? these things are tiny they should never need to be dynamically allocated pointers

Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

still here

CMakeLists.txt Outdated
add_executable(merge_maps_tool src/merge_maps_tool.cpp)
add_dependencies(merge_maps_tool ${PROJECT_NAME}_generate_messages_cpp)
target_link_libraries(merge_maps_tool ${catkin_LIBRARIES} ${Boost_LIBRARIES})
add_executable(merge_maps_kinetic src/merge_maps_kinetic.cpp)
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think you mean "_kinematic" not "_kinetic"

CMakeLists.txt Outdated

install(TARGETS slam_toolbox merge_maps_tool spa_solver_plugin g2O_solver_plugin ceres_solver_plugin SlamToolboxPlugin
#### Merging maps optimizaiton
add_executable(merge_maps_optimization src/merge_maps_optimization.cpp)
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Please take out all your merge maps optimization work out of this PR unless its complete. Meta-PRs are impossible to review

use_response_expansion: true

#serialization params
load_previous_mapper: true No newline at end of file
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I dont see anyone that uses this.... remove?

scan_filter_->registerCallback(boost::bind(&SlamToolbox::LaserCallback, this, _1));
marker_publisher_ = node.advertise<visualization_msgs::MarkerArray>("karto_graph_visualization",1);
scan_publisher_ = node.advertise<sensor_msgs::LaserScan>("karto_scan_visualization",10);
ssSerialize_ = node.advertiseService("serialize_map", &SlamToolbox::SerializePoseGraphCallback, this);
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

line up characters

lasers_.begin();
for (it; it!=lasers_.end(); ++it)
{

Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

space?

slam_toolbox::SerializePoseGraph::Response &resp)
/*****************************************************************************/
{
const std::string filename = req.filename + std::string(".st");
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

why did you remove the file ending?

return true;
}

bool SlamToolbox::ReloadMapperCallback(slam_toolbox::AddSubmap::Request &req, slam_toolbox::AddSubmap::Response &resp)
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

add /**/s

karto::SensorManager::GetInstance()->RegisterSensor(pSensor);
lasers_["base_laser_link"] = laser;
}

Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

space?

void KartoToROSOccupancyGrid(const karto::LocalizedRangeScanVector& scans, nav_msgs::GetMap::Response& map);

inline bool FileExists(const std::string& name)
karto::Pose2 ApplyCorrection(const karto::Pose2& pose, const tf::Transform& submap_correction)
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why are these defined in the header?

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

because there are 2 for different data types so i thought it would be nicer to have them in the header, I can return them to the source file

Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

please

Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

^ plz move <3

tf::Transform pose_tf, pose_corr;
pose_tf.setOrigin(tf::Vector3(pose.GetX(), pose.GetY(), 0.));
pose_tf.setRotation(tf::createQuaternionFromRPY(0, 0, pose.GetHeading()));
pose_corr = submap_correction*pose_tf;
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

add space between multiplication operator, here and in the function below

// state
bool IsPaused(const PausedApplication& app);

bool LoadMapperCallback(slam_toolbox::AddSubmap::Request &req, slam_toolbox::AddSubmap::Response &resp);
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Can you use another message type? rename the AddSubmap -> AddMap

_load_submap = nh.serviceClient<slam_toolbox::AddSubmap>("/merge_maps_tool/add_submap");
_merge = nh.serviceClient<slam_toolbox::MergeMaps>("/merge_maps_tool/merge_maps");
_serialize = nh.serviceClient<slam_toolbox::SerializePoseGraph>("/slam_toolbox/serialize_map");
_load_submap = nh.serviceClient<slam_toolbox::AddSubmap>("/add_submap");
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

These should be in the /map_merging namespace - probably to be shared amongst both the kinematic and optimization based approaches so they can be swapped in without changes

{
slam_toolbox::AddSubmap msg;
msg.request.filename = _line2->text().toStdString();
if (!_load_submap.call(msg))
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

rename _load_submap to _load_submap_for_merging

KartoToROSOccupancyGrid(scans,map);

tf::Transform transform;
transform.setOrigin(tf::Vector3(map.map.info.origin.position.x + map.map.info.width * map.map.info.resolution / 2.0,\
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

line lengths

map.map.info.origin.position.y + map.map.info.height * map.map.info.resolution / 2.0, 0.));
map.map.info.origin.position.x = - (map.map.info.width * map.map.info.resolution / 2.0);
map.map.info.origin.position.y = - (map.map.info.height * map.map.info.resolution / 2.0);
transform.setRotation(tf::createQuaternionFromRPY(0,0,0));
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

remove this line. Instead when you make the transform, use setIdentity(), then set the origin and delete this. You're doing quaternion math equivalent to (0,0,0,1)

mat.getRPY(roll, pitch, yaw);
tf::Transform previous_submap_correction ;
previous_submap_correction.setOrigin(tf::Vector3(submap_locations_[id](0),submap_locations_[id](1), 0.));
previous_submap_correction.setRotation(tf::createQuaternionFromRPY(0, 0, 0));
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

same thing here: setIdentity()

nh_.setParam("paused_new_measurements", pause_new_measurements_);
nh_.setParam("interactive_mode", interactive_mode_);


Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

remove space

serialization::Read(filename, mapper, dataset);
std::map<karto::Name, std::vector<karto::Vertex<karto::LocalizedRangeScan>*>> mapper_vertices = mapper->GetGraph()->GetVertices();
std::map<karto::Name, std::vector<karto::Vertex<karto::LocalizedRangeScan>*>>::iterator vertices_it;
for(vertices_it = mapper_vertices.begin(); vertices_it!=mapper_vertices.end(); ++vertices_it)
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You have vertices_it and vertex_it, that's pretty subtle, please rename

Copy link
Owner

@SteveMacenski SteveMacenski left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

All just formatting 💯 🔢 🥇 we should be able to merge tomorrow!

Lets plan on showing me live demo and video tomorrow. After I'll fire it onto a robot in a store and we can do a rough demonstration of 1) continuing mapping from dock to dock (since we dont do any offsets between runs right now) 2) merging 2 submaps kinematically 3) rviz plugin isnt broken ;)

Next steps:

  • optimization merging
  • accepting an offset for poses relative to old map frame to start (on me)
  • deleting nodes logic (on me)

std::map<karto::Name, std::vector<karto::Vertex<karto::LocalizedRangeScan>*>>::iterator vertices_it;
for(vertices_it = mapper_vertices.begin(); vertices_it!=mapper_vertices.end(); ++vertices_it)
std::map<karto::Name, std::vector<karto::Vertex<karto::LocalizedRangeScan>*>>::iterator sensor_vertex_it;
for(sensor_vertex_it = mapper_vertices.begin(); sensor_vertex_it!=mapper_vertices.end(); ++sensor_vertex_it)
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

vertex_map_it & vertix_it

void KartoToROSOccupancyGrid(const karto::LocalizedRangeScanVector& scans, nav_msgs::GetMap::Response& map);

inline bool FileExists(const std::string& name)
karto::Pose2 ApplyCorrection(const karto::Pose2& pose, const tf::Transform& submap_correction)
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

^ plz move <3


/*****************************************************************************/
void SlamToolboxPlugin::LoadPoseGraph()
void SlamToolboxPlugin::LoadMap()
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

remove extra spaces

if (!_load_submap.call(msg))
{
ROS_WARN("Failed to load pose graph from file, is service running?");
slam_toolbox::AddSubmap msg;
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This function and the next one look indented too much

std::vector<karto::LocalizedRangeScanVector>& vector_of_scans = scans_vec_;
karto::LocalizedRangeScan* pScan_copy;

for(localized_range_scans_vec_it it_LRV = vector_of_scans.begin(); it_LRV!= vector_of_scans.end(); ++it_LRV)
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

line length

pScan_copy->SetBarycenterPose(karto_baryCenterPose_corr);

//TRANSFORM BOUNDING BOX POSITIONS
karto::BoundingBox2 bbox = pScan_copy->GetBoundingBox();
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This full function needs to respect the line lengths

ros::NodeHandle private_nh("~");
nh_ = private_nh;
SetParams(private_nh);

Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

rm space

@@ -1060,17 +1064,77 @@ void SlamToolbox::MoveNode(const int& id, const Eigen::Vector3d& pose, \
mapper_->CorrectPoses();
}
}
Copy link
Owner

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

add this space back between functions

@SteveMacenski SteveMacenski merged commit 44e425e into SteveMacenski:serialization Dec 12, 2018
SteveMacenski added a commit that referenced this pull request Dec 13, 2018
* serialization + merging tool starts

* second stab at serialization

* reorg

* serialization changes

* serialization updates

* Map merging (#5)

* use binary archive for serialization, initialize laser to get sensor data, add transform initialization

* connect visualization markers with submaps

* try merging

* add transforms

* SAD SAD transforms

* working transform

* put submap origins in to zeros, map submap id and transform

* fix case when there is no transform applied

* submap markers put in the center of each submap, requested fixes

* small changes

* add typedefs for iterators, rename vars

* requested fixes

* fix

* fix

* again fix

* refactor ApplyCorrection fcn

* switch to unique pointers

* add ref

* prepare for merginggg

* load laser dataset

* add continuous slamming

* add continuous slamming, gui buttons for rviz tool

* add merge_map_kietic header

* register sensor, add to laser map

* fix

* remove mem alloc, leak, rename buttons, functions

* remove merge optimization work for PR

* organize

* unnecessary function input

* fix naming

* switch lines in rviz gui

* lineup

* change {sub}map names

* fixes

* fix service name

* add service namespace, rename, change tf handling

* fix

* line lengths, renaming, header func fix

* fix package version
malban pushed a commit to malban/slam_toolbox that referenced this pull request Jul 7, 2022
…ality. (SteveMacenski#5)

* Modified pause behavior. Added reset service

* One last book keeping issue. Dont publish graph without subscribers

* Add start/stop service
malban pushed a commit to malban/slam_toolbox that referenced this pull request Jul 19, 2022
…ality. (SteveMacenski#5)

* Modified pause behavior. Added reset service

* One last book keeping issue. Dont publish graph without subscribers

* Add start/stop service
malban pushed a commit to malban/slam_toolbox that referenced this pull request Jul 19, 2022
…ality. (SteveMacenski#5)

* Modified pause behavior. Added reset service

* One last book keeping issue. Dont publish graph without subscribers

* Add start/stop service
malban added a commit to malban/slam_toolbox that referenced this pull request Sep 22, 2022
* Add graph edges to graph visualization marker. (SteveMacenski#502)

* Clear markers for graph visualization to account for removed nodes. (SteveMacenski#503)

* Publish PoseWithCovarianceStamped message with each scan match. (SteveMacenski#504)

* Publish PoseWithCovarianceStamped message with each scan match.

* Refactor code to return covariance as a output parameter instead of storing in the range scan object.

* Linting fixes.

* Publish pose with covariance in localization mode. (SteveMacenski#508)

* Visualize localization nodes and edges with different colors in the pose graph marker message. (SteveMacenski#509)

* Add map_and_localization node that supports toggling between mapping and localization modes with a service. (SteveMacenski#510)

* Stop ceres problem from freeing loss function (SteveMacenski#519) (SteveMacenski#520)

Co-authored-by: john-maidbot <78750993+john-maidbot@users.noreply.github.com>

* Experimental changes.

* Initial experiments (pose w cov stamped for each scan msg, better graph edge vis, tweak to continuous scan matching, etc) (SteveMacenski#2)

* Add option to perform continuous scan matching to update the transform and pose even when the minimum travel distance or heading have not been reached for adding the scan into the map.

* Add graph edges to graph visualization marker. (SteveMacenski#502)

* Clear markers for graph visualization to account for removed nodes. (SteveMacenski#503)

* Publish PoseWithCovarianceStamped message with each scan match. (SteveMacenski#504)

* Publish PoseWithCovarianceStamped message with each scan match.

* Refactor code to return covariance as a output parameter instead of storing in the range scan object.

* Linting fixes.

* Tweaks to parameter documentation.

* Refactor scan match only logic to be based on a time interval.

* Need to install async_pruned_slam_toolbox lib

* Add localization status publisher (SteveMacenski#3)

* Lint slam_toolbox_async_pruned.cpp

* Change a lot of INFO prints related to pruning to DEBUG

* Modified pause behavior. Added start/stop services and reset functionality. (SteveMacenski#5)

* Modified pause behavior. Added reset service

* One last book keeping issue. Dont publish graph without subscribers

* Add start/stop service

* Enable switching from mapping to localization mode (SteveMacenski#6)

* Lidar qos is sensor data (best effort) (SteveMacenski#7)

* Lidar qos is sensor data (best effort)

* typo

* Set initial slam pose via subscription (SteveMacenski#8)

* Freeze map nodes when localizing + don't partition the graph when popping localization nodes + don't crash when resetting in localization mode (SteveMacenski#9)

* Set non-localization nodes to constant

* Forbid removing localization nodes if we don't have enough connections to the map graph

* Fix crash on reset

* unfreeze nodes when exiting localization mode

* Don't freeze nodes that aren't part of the problem yet

* Merge fixes.

* Support resetting mapping pose.

Co-authored-by: Marc Alban <marcalban@gmail.com>
Co-authored-by: Marc Alban <marcalban@hatchbed.com>
Co-authored-by: Justin Nguyen <justin@maidbot.com>
Co-authored-by: Ketan Kharche <47426551+ketan-maidbot@users.noreply.github.com>
jsongCMU pushed a commit to jsongCMU/slam_toolbox that referenced this pull request Oct 16, 2022
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

2 participants