43 #include <nav_msgs/Odometry.h> 44 #include <tf/tfMessage.h> 180 const std::string& drive_motor_name,
181 const std::string& steer_motor_name);
double left_wheel_radius_multiplier_
double right_wheel_radius_multiplier_
boost::shared_ptr< realtime_tools::RealtimePublisher< nav_msgs::Odometry > > odom_pub_
Odometry related:
ros::Duration publish_period_
Odometry related:
Velocity command related:
geometry_msgs::TransformStamped odom_frame_
hardware_interface::JointHandle drive_motor_input_
Hardware handles:
SpeedLimiter limiter_ang_
void cmdVelCallback(const geometry_msgs::Twist &command)
Velocity command callback.
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< Commands > command_
bool init(hardware_interface::VelocityJointInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Initialize controller.
double drive_motor_gear_ratio_
The Odometry class handles odometry readings (2D pose and velocity with related timestamp) ...
double wheel_separation_multiplier_
Wheel separation and radius calibration multipliers:
void stopping(const ros::Time &time)
Stops controller.
double wheel_radius_
Wheel radius (assuming it's the same for the left and right wheels):
bool enable_odom_tf_
Whether to publish odometry to tf or not:
SpeedLimiter limiter_lin_
size_t wheel_joints_size_
Number of wheel joints:
hardware_interface::JointHandle steer_motor_input_
std::string base_frame_id_
Frame to use for the robot base:
double steer_motor_gear_ratio_
DoubleDiffDriveController()
boost::shared_ptr< realtime_tools::RealtimePublisher< tf::tfMessage > > tf_odom_pub_
void brake()
Brakes the wheels, i.e. sets the velocity to 0.
PLUGINLIB_EXPORT_CLASS(RobotLocalization::EkfNodelet, nodelet::Nodelet)
void setupRtPublishersMsg(ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Sets the odometry publishing fields.
ros::Time last_state_publish_time_
ros::Subscriber sub_command_
double wheel_separation_
Wheel separation, wrt the midpoint of the wheel width:
bool setWheelParamsFromUrdf(ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, const std::string &drive_motor_name, const std::string &steer_motor_name)
Sets odometry parameters from the URDF, i.e. the wheel radius and separation.
double cmd_vel_timeout_
Timeout to consider cmd_vel commands old:
void starting(const ros::Time &time)
Starts controller.