44 #include <nav_msgs/Odometry.h> 45 #include <tf/tfMessage.h> 66 hardware_interface::PositionJointInterface,
67 hardware_interface::VelocityJointInterface>
189 const std::string rear_wheel_name,
190 const std::string front_steer_name,
191 bool lookup_wheel_separation_h,
192 bool lookup_wheel_radius);
AckermannSteeringController()
diff_drive_controller::SpeedLimiter limiter_lin_
realtime_tools::RealtimeBuffer< Commands > command_
void starting(const ros::Time &time)
Starts controller.
void update(const ros::Time &time, const ros::Duration &period)
Updates controller, i.e. computes the odometry and sets the new velocity commands.
double wheel_radius_multiplier_
bool enable_odom_tf_
Whether to publish odometry to tf or not:
void brake()
Brakes the wheels, i.e. sets the velocity to 0.
The Odometry class handles odometry readings (2D pose and velocity with related timestamp) ...
void stopping(const ros::Time &)
Stops controller.
boost::shared_ptr< realtime_tools::RealtimePublisher< nav_msgs::Odometry > > odom_pub_
Odometry related:
hardware_interface::JointHandle front_steer_joint_
std::string base_frame_id_
Frame to use for the robot base:
double steer_pos_multiplier_
ros::Duration publish_period_
Odometry related:
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Initialize controller.
bool setOdomParamsFromUrdf(ros::NodeHandle &root_nh, const std::string rear_wheel_name, const std::string front_steer_name, bool lookup_wheel_separation_h, bool lookup_wheel_radius)
Sets odometry parameters from the URDF, i.e. the wheel radius and separation.
double wheel_separation_h_multiplier_
Wheel separation and radius calibration multipliers:
size_t steer_joints_size_
Number of steer joints:
ros::Time last_state_publish_time_
std::string odom_frame_id_
Frame to use for odometry and odom tf:
bool allow_multiple_cmd_vel_publishers_
Whether to allow multiple publishers on cmd_vel topic or not:
diff_drive_controller::SpeedLimiter limiter_ang_
ros::Subscriber sub_command_
double cmd_vel_timeout_
Timeout to consider cmd_vel commands old:
size_t wheel_joints_size_
Number of wheel joints:
double wheel_separation_h_
Wheel separation, wrt the midpoint of the wheel width:
hardware_interface::JointHandle rear_wheel_joint_
Hardware handles:
Commands last1_cmd_
Speed limiters:
boost::shared_ptr< realtime_tools::RealtimePublisher< tf::tfMessage > > tf_odom_pub_
void setOdomPubFields(ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Sets the odometry publishing fields.
Velocity command related:
double wheel_radius_
Wheel radius (assuming it's the same for the left and right wheels):
void cmdVelCallback(const geometry_msgs::Twist &command)
Velocity command callback.