42 #include <dynamic_reconfigure/server.h> 44 #include <geometry_msgs/TwistStamped.h> 45 #include <nav_msgs/Odometry.h> 46 #include <tf/tfMessage.h> 53 #include <diff_drive_controller/DiffDriveControllerConfig.h> 188 : left_wheel_radius_multiplier(1.0)
189 , right_wheel_radius_multiplier(1.0)
190 , wheel_separation_multiplier(1.0)
193 , enable_odom_tf(true)
198 os <<
"DynamicParams:\n" 200 <<
"\tOdometry parameters:\n" 205 <<
"\tPublication parameters:\n" 206 <<
"\t\tPublish executed velocity command: " << params.
publish_cmd <<
"\n" 207 <<
"\t\tPublication rate: " << params.
publish_rate <<
"\n" 241 const std::string& wheel_param,
242 std::vector<std::string>& wheel_names);
251 const std::string& left_wheel_name,
252 const std::string& right_wheel_name,
253 bool lookup_wheel_separation,
254 bool lookup_wheel_radius);
269 void reconfCallback(DiffDriveControllerConfig& config, uint32_t );
realtime_tools::RealtimeBuffer< Commands > command_
bool allow_multiple_cmd_vel_publishers_
Whether to allow multiple publishers on cmd_vel topic or not:
bool init(hardware_interface::VelocityJointInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Initialize controller.
double wheel_separation_
Wheel separation, wrt the midpoint of the wheel width:
void updateDynamicParams()
Update the dynamic parameters in the RT loop.
double wheel_separation_multiplier
std::vector< hardware_interface::JointHandle > left_wheel_joints_
Hardware handles:
Velocity command related:
double wheel_radius_
Wheel radius (assuming it's the same for the left and right wheels):
std::string odom_frame_id_
Frame to use for odometry and odom tf:
void brake()
Brakes the wheels, i.e. sets the velocity to 0.
size_t wheel_joints_size_
Number of wheel joints:
bool getWheelNames(ros::NodeHandle &controller_nh, const std::string &wheel_param, std::vector< std::string > &wheel_names)
Get the wheel names from a wheel param.
PLUGINLIB_EXPORT_CLASS(diff_drive_controller::DiffDriveController, controller_interface::ControllerBase)
double right_wheel_radius_multiplier
std::vector< hardware_interface::JointHandle > right_wheel_joints_
void starting(const ros::Time &time)
Starts controller.
boost::shared_ptr< ReconfigureServer > dyn_reconf_server_
void cmdVelCallback(const geometry_msgs::Twist &command)
Velocity command callback.
ros::Time last_state_publish_time_
ros::Subscriber sub_command_
void update(const ros::Time &time, const ros::Duration &period)
Updates controller, i.e. computes the odometry and sets the new velocity commands.
realtime_tools::RealtimeBuffer< DynamicParams > dynamic_params_
The Odometry class handles odometry readings (2D pose and velocity with related timestamp) ...
double right_wheel_radius_multiplier_
ros::Duration publish_period_
Odometry related:
double left_wheel_radius_multiplier
boost::shared_ptr< realtime_tools::RealtimePublisher< nav_msgs::Odometry > > odom_pub_
Odometry related:
bool publish_cmd_
Publish limited velocity:
SpeedLimiter limiter_lin_
double cmd_vel_timeout_
Timeout to consider cmd_vel commands old:
boost::shared_ptr< realtime_tools::RealtimePublisher< tf::tfMessage > > tf_odom_pub_
friend std::ostream & operator<<(std::ostream &os, const DynamicParams ¶ms)
SpeedLimiter limiter_ang_
bool setOdomParamsFromUrdf(ros::NodeHandle &root_nh, const std::string &left_wheel_name, const std::string &right_wheel_name, bool lookup_wheel_separation, bool lookup_wheel_radius)
Sets odometry parameters from the URDF, i.e. the wheel radius and separation.
double left_wheel_radius_multiplier_
bool enable_odom_tf_
Whether to publish odometry to tf or not:
Commands last1_cmd_
Speed limiters:
void reconfCallback(DiffDriveControllerConfig &config, uint32_t)
Callback for dynamic_reconfigure server.
boost::shared_ptr< realtime_tools::RealtimePublisher< geometry_msgs::TwistStamped > > cmd_vel_pub_
Publish executed commands.
void setOdomPubFields(ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Sets the odometry publishing fields.
dynamic_reconfigure::Server< DiffDriveControllerConfig > ReconfigureServer
Dynamic Reconfigure server.
void stopping(const ros::Time &)
Stops controller.
double wheel_separation_multiplier_
Wheel separation and radius calibration multipliers:
std::string base_frame_id_
Frame to use for the robot base: