Skip to content
This repository is currently being migrated. It's locked while the migration is in progress.

Commit

Permalink
Improved Overall readablity (ros-planning#1177)
Browse files Browse the repository at this point in the history
  • Loading branch information
shubham-shahh authored Nov 18, 2021
1 parent 19eddca commit 6e9de3f
Show file tree
Hide file tree
Showing 4 changed files with 7 additions and 7 deletions.
2 changes: 1 addition & 1 deletion amcl/cfg/AMCL.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ gen.add("min_particles", int_t, 0, "Minimum allowed number of particles.", 100,
gen.add("max_particles", int_t, 0, "Mamimum allowed number of particles.", 5000, 0, 10000)

gen.add("kld_err", double_t, 0, "Maximum error between the true distribution and the estimated distribution.", .01, 0, 1)
gen.add("kld_z", double_t, 0, "Upper standard normal quantile for (1 - p), where p is the probability that the error on the estimated distrubition will be less than kld_err.", .99, 0, 1)
gen.add("kld_z", double_t, 0, "Upper standard normal quantile for (1 - p), where p is the probability that the error on the estimated distribution will be less than kld_err.", .99, 0, 1)

gen.add("update_min_d", double_t, 0, "Translational movement required before performing a filter update.", .2, 0, 5)
gen.add("update_min_a", double_t, 0, "Rotational movement required before performing a filter update.", pi/6, 0, 2*pi)
Expand Down
2 changes: 1 addition & 1 deletion amcl/src/amcl/pf/pf.c
Original file line number Diff line number Diff line change
Expand Up @@ -132,7 +132,7 @@ void pf_free(pf_t *pf)
return;
}

// Initialize the filter using a guassian
// Initialize the filter using a gaussian
void pf_init(pf_t *pf, pf_vector_t mean, pf_matrix_t cov)
{
int i;
Expand Down
2 changes: 1 addition & 1 deletion amcl/src/amcl/sensors/amcl_laser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -330,7 +330,7 @@ double AMCLLaser::LikelihoodFieldModelProb(AMCLLaserData *data, pf_sample_set_t*

double max_dist_prob = exp(-(self->map->max_occ_dist * self->map->max_occ_dist) / z_hit_denom);

//Beam skipping - ignores beams for which a majoirty of particles do not agree with the map
//Beam skipping - ignores beams for which a majority of particles do not agree with the map
//prevents correct particles from getting down weighted because of unexpected obstacles
//such as humans

Expand Down
8 changes: 4 additions & 4 deletions amcl/src/amcl_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -181,13 +181,13 @@ class AmclNode
void updatePoseFromServer();
void applyInitialPose();

//parameter for what odom to use
//parameter for which odom to use
std::string odom_frame_id_;

//paramater to store latest odom pose
geometry_msgs::PoseStamped latest_odom_pose_;

//parameter for what base to use
//parameter for which base to use
std::string base_frame_id_;
std::string global_frame_id_;

Expand Down Expand Up @@ -696,7 +696,7 @@ void AmclNode::runFromBag(const std::string &in_bag_fn, bool trigger_global_loca
break;
}
}
ROS_INFO("Waiting for map...");
ROS_INFO("Waiting for the map...");
ros::getGlobalCallbackQueue()->callAvailable(ros::WallDuration(1.0));
}

Expand Down Expand Up @@ -976,7 +976,7 @@ AmclNode::freeMapDependentMemory()

/**
* Convert an OccupancyGrid map message into the internal
* representation. This allocates a map_t and returns it.
* representation. This allocates a map_t and returns it.
*/
map_t*
AmclNode::convertMap( const nav_msgs::OccupancyGrid& map_msg )
Expand Down

0 comments on commit 6e9de3f

Please sign in to comment.