43 #include <nav_msgs/Odometry.h> 44 #include <tf/tfMessage.h> 121 Commands() : linX(0.0), linY(0.0), ang(0.0), stamp(0.0) {}
181 const std::string& wheel0_name,
182 const std::string& wheel1_name,
183 const std::string& wheel2_name,
184 const std::string& wheel3_name);
192 bool getWheelRadius(
const urdf::ModelInterfaceSharedPtr model,
const urdf::LinkConstSharedPtr& wheel_link,
double& wheel_radius);
ros::Duration publish_period_
Odometry related:
double cmd_vel_timeout_
Timeout to consider cmd_vel commands old:
ros::Subscriber sub_command_
hardware_interface::JointHandle wheel1_jointHandle_
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 getWheelRadius(const urdf::ModelInterfaceSharedPtr model, const urdf::LinkConstSharedPtr &wheel_link, double &wheel_radius)
Get the radius of a given wheel.
void brake()
Brakes the wheels, i.e. sets the velocity to 0.
ros::Time last_state_publish_time_
boost::shared_ptr< realtime_tools::RealtimePublisher< tf::tfMessage > > tf_odom_pub_
std::string odom_frame_id_
void starting(const ros::Time &time)
Starts controller.
hardware_interface::JointHandle wheel3_jointHandle_
void setupRtPublishersMsg(ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Sets the odometry publishing fields.
hardware_interface::JointHandle wheel2_jointHandle_
bool setWheelParamsFromUrdf(ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, const std::string &wheel0_name, const std::string &wheel1_name, const std::string &wheel2_name, const std::string &wheel3_name)
Sets odometry parameters from the URDF, i.e. the wheel radius and separation.
double wheel_separation_x_
boost::shared_ptr< realtime_tools::RealtimePublisher< nav_msgs::Odometry > > odom_pub_
Odometry related:
void stopping(const ros::Time &time)
Stops controller.
bool use_realigned_roller_joints_
Wheel radius (assuming it's the same for the left and right wheels):
void cmdVelCallback(const geometry_msgs::Twist &command)
Velocity command callback.
bool init(hardware_interface::VelocityJointInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Initialize controller.
hardware_interface::JointHandle wheel0_jointHandle_
Hardware handles:
SpeedLimiter limiter_ang_
Velocity command related:
SpeedLimiter limiter_linY_
std::string base_frame_id_
Frame to use for the robot base:
double wheel_separation_y_
geometry_msgs::TransformStamped odom_frame_
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
size_t wheel_joints_size_
Number of wheel joints:
The Odometry class handles odometry readings (2D pose and velocity with related timestamp) ...
bool enable_odom_tf_
Whether to publish odometry to tf or not:
SpeedLimiter limiter_linX_