Go to the documentation of this file.
42 #include <control_msgs/JointTrajectoryControllerState.h>
44 #include <diff_drive_controller/DiffDriveControllerConfig.h>
47 #include <dynamic_reconfigure/server.h>
48 #include <geometry_msgs/TwistStamped.h>
51 #include <nav_msgs/Odometry.h>
54 #include <tf/tfMessage.h>
139 std::shared_ptr<realtime_tools::RealtimePublisher<geometry_msgs::TwistStamped> >
cmd_vel_pub_;
142 std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::Odometry> >
odom_pub_;
143 std::shared_ptr<realtime_tools::RealtimePublisher<tf::tfMessage> >
tf_odom_pub_;
147 std::shared_ptr<realtime_tools::RealtimePublisher<control_msgs::JointTrajectoryControllerState> >
controller_state_pub_;
216 os <<
"DynamicParams:\n"
218 <<
"\tOdometry parameters:\n"
223 <<
"\tPublication parameters:\n"
224 <<
"\t\tPublish executed velocity command: " << (params.
publish_cmd?
"enabled":
"disabled") <<
"\n"
226 <<
"\t\tPublish frame odom on tf: " << (params.
enable_odom_tf?
"enabled":
"disabled");
235 typedef dynamic_reconfigure::Server<DiffDriveControllerConfig>
ReconfigureServer;
260 const std::string& wheel_param,
261 std::vector<std::string>& wheel_names);
270 const std::string& left_wheel_name,
271 const std::string& right_wheel_name,
272 bool lookup_wheel_separation,
273 bool lookup_wheel_radius);
288 void reconfCallback(DiffDriveControllerConfig& config, uint32_t );
307 double wheel_separation,
308 double left_wheel_radius,
309 double right_wheel_radius);
bool publish_wheel_joint_controller_state_
Publish wheel data:
ros::Subscriber sub_command_
ros::Duration publish_period_
Odometry related:
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
dynamic_reconfigure::Server< DiffDriveControllerConfig > ReconfigureServer
Dynamic Reconfigure server.
std::shared_ptr< ReconfigureServer > dyn_reconf_server_
friend std::ostream & operator<<(std::ostream &os, const DynamicParams ¶ms)
double vel_left_desired_previous_
Previous velocities from the encoders:
bool init(hardware_interface::VelocityJointInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Initialize controller.
std::vector< double > vel_right_previous_
std::vector< hardware_interface::JointHandle > right_wheel_joints_
void update(const ros::Time &time, const ros::Duration &period)
Updates controller, i.e. computes the odometry and sets the new velocity commands.
bool publish_cmd_
Publish limited velocity:
std::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.
double cmd_vel_timeout_
Timeout to consider cmd_vel commands old:
double vel_right_desired_previous_
realtime_tools::RealtimeBuffer< DynamicParams > dynamic_params_
boost::recursive_mutex dyn_reconf_server_mutex_
realtime_tools::RealtimeBuffer< Commands > command_
SpeedLimiter limiter_ang_
void stopping(const ros::Time &)
Stops controller.
double wheel_separation_multiplier
bool allow_multiple_cmd_vel_publishers_
Whether to allow multiple publishers on cmd_vel topic or not:
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.
bool enable_odom_tf_
Whether to publish odometry to tf or not:
void brake()
Brakes the wheels, i.e. sets the velocity to 0.
std::vector< hardware_interface::JointHandle > left_wheel_joints_
Hardware handles:
double wheel_separation_multiplier_
Wheel separation and radius calibration multipliers:
double wheel_radius_
Wheel radius (assuming it's the same for the left and right wheels):
Commands last1_cmd_
Speed limiters:
double left_wheel_radius_multiplier_
std::string base_frame_id_
Frame to use for the robot base:
std::shared_ptr< realtime_tools::RealtimePublisher< nav_msgs::Odometry > > odom_pub_
Odometry related:
std::string odom_frame_id_
Frame to use for odometry and odom tf:
void reconfCallback(DiffDriveControllerConfig &config, uint32_t)
Callback for dynamic_reconfigure server.
Velocity command related:
std::shared_ptr< realtime_tools::RealtimePublisher< tf::tfMessage > > tf_odom_pub_
double wheel_separation_
Wheel separation, wrt the midpoint of the wheel width:
void updateDynamicParams()
Update the dynamic parameters in the RT loop.
void publishWheelData(const ros::Time &time, const ros::Duration &period, Commands &curr_cmd, double wheel_separation, double left_wheel_radius, double right_wheel_radius)
std::vector< double > vel_left_previous_
Previous velocities from the encoders:
std::shared_ptr< realtime_tools::RealtimePublisher< control_msgs::JointTrajectoryControllerState > > controller_state_pub_
Controller state publisher.
void cmdVelCallback(const geometry_msgs::Twist &command)
Velocity command callback.
double right_wheel_radius_multiplier_
SpeedLimiter limiter_lin_
void starting(const ros::Time &time)
Starts controller.
double right_wheel_radius_multiplier
ros::Time last_state_publish_time_
The Odometry class handles odometry readings (2D pose and velocity with related timestamp)