Skip to content

Commit

Permalink
Changed some comments
Browse files Browse the repository at this point in the history
  • Loading branch information
plnegre committed Jan 21, 2014
1 parent 91ed536 commit aee2701
Show file tree
Hide file tree
Showing 3 changed files with 9 additions and 12 deletions.
12 changes: 5 additions & 7 deletions include/stereo_slam_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -56,14 +56,16 @@ class StereoSlamBase

// G2O Optimization
double update_rate; //!> Timer callback rate (in seconds) to optimize the graph.
int g2o_algorithm; //!> Set to 0 for LinearSlam Solver. Set to 1 for.
int g2o_algorithm; //!> Set to 0 for LinearSlam Solver with gauss-newton. Set to 1 for LinearSlam Solver with Levenberg.
int go2_opt_max_iter; //!> Maximum number of iteration for the graph optimization.
bool go2_verbose; //!> True to output the g2o iteration messages

// Odometry operational parameters
// Graph operational parameters
double min_displacement; //!> Minimum odometry displacement between poses to be saved as graph vertices.
double max_candidate_threshold; //!> Maximum distance between graph vertices to be considered for possible candidates of loop closure.
int neighbor_offset; //!> Number of neighbor nodes discarted for loop-closing.
bool save_graph_to_file; //!> True if user wants to save the graph into file.
std::string files_path; //!> Path where save the graph data.

// Stereo vision parameters
std::string desc_type; //!> Descriptor type can be SIFT or SURF
Expand All @@ -73,7 +75,7 @@ class StereoSlamBase
int min_inliers; //!> Minimum number of inliers found by solvePnPRansac to take into account the edge in the graph.
int max_inliers; //!> Maximum number of inliers for solvePnPRansac, stop if more inliers than this are found.
int max_solvepnp_iter; //!> Maximum number of interations of the solvePnPRansac algorithm.
double allowed_reprojection_err; //!> Maximum reprojection error allowd in solvePnPRansa algorithm.
double allowed_reprojection_err; //!> Maximum reprojection error allowed in solvePnPRansac algorithm.
double max_edge_err; //!> Maximum pose difference to take the new edge as valid.
bool stereo_vision_verbose; //!> True to output the messages of stereo matching process, false otherwise.
int bucket_width; //!> Bucket width.
Expand All @@ -85,10 +87,6 @@ class StereoSlamBase
std::string map_frame_id; //!> The map frame id.
std::string base_link_frame_id; //!> The robot base link frame id.

// Graph to file paraneter
bool save_graph_to_file; //!> True if user wants to save the graph into file.
std::string files_path; //!> Path where save the graph data.

// Default values
static const double DEFAULT_UPDATE_RATE = 3.0;
static const int DEFAULT_G2O_ALGORITHM = 1;
Expand Down
2 changes: 1 addition & 1 deletion launch/demo.launch
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@

<!-- Parameters -->

<!-- Min displacement (in meters) between graph vertices -->
<!-- Min displacement between graph vertices (in meters) -->
<param name="min_displacement" value="0.25"/>

<!-- Candidate search radius (in meters) -->
Expand Down
7 changes: 3 additions & 4 deletions src/stereo_slam_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -207,10 +207,12 @@ void stereo_slam::StereoSlamBase::readParameters()
nh_private_.param("go2_opt_max_iter", stereo_slam_params.go2_opt_max_iter, stereo_slam_params.DEFAULT_G2O_OPT_MAX_ITER);
nh_private_.param("go2_verbose", stereo_slam_params.go2_verbose, stereo_slam_params.DEFAULT_G2O_VERBOSE);

// Odometry operational parameters
// Graph operational parameters
nh_private_.param("min_displacement", stereo_slam_params.min_displacement, stereo_slam_params.DEFAULT_MIN_DISPLACEMENT);
nh_private_.param("max_candidate_threshold", stereo_slam_params.max_candidate_threshold, stereo_slam_params.DEFAULT_MAX_CANDIDATE_THRESHOLD);
nh_private_.param("neighbor_offset", stereo_slam_params.neighbor_offset, stereo_slam_params.DEFAULT_NEIGHBOR_OFFSET);
nh_private_.param("save_graph_to_file", stereo_slam_params.save_graph_to_file, stereo_slam_params.DEFAULT_SAVE_GRAPH_TO_FILE);
nh_private_.param("files_path", stereo_slam_params.files_path, std::string("/home"));

// Stereo vision parameters
nh_private_.param("desc_type", stereo_slam_params.desc_type, std::string("SIFT"));
Expand All @@ -232,9 +234,6 @@ void stereo_slam::StereoSlamBase::readParameters()
nh_private_.param("map_frame_id", stereo_slam_params.map_frame_id, std::string("/map"));
nh_private_.param("base_link_frame_id", stereo_slam_params.base_link_frame_id, std::string("/base_link"));

// Graph to file parameters
nh_private_.param("save_graph_to_file", stereo_slam_params.save_graph_to_file, stereo_slam_params.DEFAULT_SAVE_GRAPH_TO_FILE);
nh_private_.param("files_path", stereo_slam_params.files_path, std::string("/home"));
setParams(stereo_slam_params);

// Topics subscriptions
Expand Down

0 comments on commit aee2701

Please sign in to comment.