39 #include <nav_msgs/Odometry.h>    40 #include <four_wheel_steering_msgs/FourWheelSteeringStamped.h>    41 #include <tf/tfMessage.h>    62                                                               hardware_interface::PositionJointInterface>
   131       Command4ws() : lin(0.0), front_steering(0.0), rear_steering(0.0) {}
   218                        const std::string& wheel_param,
   219                        std::vector<std::string>& wheel_names);
 
void stopping(const ros::Time &)
Stops controller. 
ros::Subscriber sub_command_four_wheel_steering_
double cmd_vel_timeout_
Timeout to consider cmd_vel commands old: 
void cmdVelCallback(const geometry_msgs::Twist &command)
Velocity command callback. 
std::string base_frame_id_
Frame to use for the robot base: 
void updateCommand(const ros::Time &time, const ros::Duration &period)
Compute and publish command. 
std::vector< hardware_interface::JointHandle > front_steering_joints_
std::vector< hardware_interface::JointHandle > rear_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. 
CommandTwist command_struct_twist_
void updateOdometry(const ros::Time &time)
Update and publish odometry. 
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Initialize controller. 
std::vector< hardware_interface::JointHandle > rear_steering_joints_
void cmdFourWheelSteeringCallback(const four_wheel_steering_msgs::FourWheelSteering &command)
Velocity and steering command callback. 
The Odometry class handles odometry readings (2D pose and velocity with related timestamp) ...
bool enable_twist_cmd_
Whether the control is make with four_wheel_steering msg or twist msg: 
double wheel_steering_y_offset_
double wheel_radius_
Wheel radius (assuming it's the same for the left and right wheels): 
std::vector< hardware_interface::JointHandle > front_wheel_joints_
Hardware handles: 
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. 
ros::Subscriber sub_command_
boost::shared_ptr< realtime_tools::RealtimePublisher< tf::tfMessage > > tf_odom_pub_
ros::Time last_state_publish_time_
void setOdomPubFields(ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Sets the odometry publishing fields. 
PLUGINLIB_EXPORT_CLASS(four_wheel_steering_controller::FourWheelSteeringController, controller_interface::ControllerBase)
bool enable_odom_tf_
Whether to publish odometry to tf or not: 
void brake()
Brakes the wheels, i.e. sets the velocity to 0. 
ros::Duration publish_period_
Odometry related: 
boost::shared_ptr< realtime_tools::RealtimePublisher< nav_msgs::Odometry > > odom_pub_
Odometry related: 
Velocity command related: 
FourWheelSteeringController()
void starting(const ros::Time &time)
Starts controller. 
realtime_tools::RealtimeBuffer< CommandTwist > command_twist_
Command4ws command_struct_four_wheel_steering_
SpeedLimiter limiter_ang_
boost::shared_ptr< realtime_tools::RealtimePublisher< four_wheel_steering_msgs::FourWheelSteeringStamped > > odom_4ws_pub_
CommandTwist last1_cmd_
Speed limiters: 
double track_
Wheel separation (or track), distance between left and right wheels (from the midpoint of the wheel w...
double wheel_base_
Wheel base (distance between front and rear wheel): 
realtime_tools::RealtimeBuffer< Command4ws > command_four_wheel_steering_
FourWheelSteering command related: 
SpeedLimiter limiter_lin_