Skip to content

Commit

Permalink
getOdom is const (#100)
Browse files Browse the repository at this point in the history
  • Loading branch information
renan028 authored Oct 28, 2024
1 parent 294ee8b commit 48b6977
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ class OdometryHelperRos {
*/
void odomCallback(const nav_msgs::Odometry::ConstPtr& msg);

void getOdom(nav_msgs::Odometry& base_odom);
void getOdom(nav_msgs::Odometry& base_odom) const;

void getRobotVel(geometry_msgs::PoseStamped& robot_vel);

Expand All @@ -82,7 +82,7 @@ class OdometryHelperRos {
// we listen on odometry on the odom topic
ros::Subscriber odom_sub_;
nav_msgs::Odometry base_odom_;
boost::mutex odom_mutex_;
mutable boost::mutex odom_mutex_;
// global tf frame id
std::string frame_id_; ///< The frame_id associated this data
};
Expand Down
2 changes: 1 addition & 1 deletion base_local_planner/src/odometry_helper_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ void OdometryHelperRos::odomCallback(const nav_msgs::Odometry::ConstPtr& msg) {
}

//copy over the odometry information
void OdometryHelperRos::getOdom(nav_msgs::Odometry& base_odom) {
void OdometryHelperRos::getOdom(nav_msgs::Odometry& base_odom) const {
boost::mutex::scoped_lock lock(odom_mutex_);
base_odom = base_odom_;
}
Expand Down

0 comments on commit 48b6977

Please sign in to comment.