Go to the documentation of this file.
42 #include <nav_msgs/Odometry.h>
43 #include <four_wheel_steering_msgs/FourWheelSteeringStamped.h>
44 #include <tf/tfMessage.h>
65 hardware_interface::PositionJointInterface>
120 struct CommandTwist : Command
128 struct Command4ws : Command
146 std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::Odometry> >
odom_pub_;
147 std::shared_ptr<realtime_tools::RealtimePublisher<four_wheel_steering_msgs::FourWheelSteeringStamped> >
odom_4ws_pub_;
148 std::shared_ptr<realtime_tools::RealtimePublisher<tf::tfMessage> >
tf_odom_pub_;
221 const std::string& wheel_param,
222 std::vector<std::string>& wheel_names);
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Initialize controller.
void stopping(const ros::Time &)
Stops controller.
ros::Time last_state_publish_time_
void starting(const ros::Time &time)
Starts controller.
double cmd_vel_timeout_
Timeout to consider cmd_vel commands old:
void setOdomPubFields(ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Sets the odometry publishing fields.
The Odometry class handles odometry readings (2D pose and velocity with related timestamp)
realtime_tools::RealtimeBuffer< CommandTwist > command_twist_
void cmdVelCallback(const geometry_msgs::Twist &command)
Velocity command callback.
std::shared_ptr< realtime_tools::RealtimePublisher< four_wheel_steering_msgs::FourWheelSteeringStamped > > odom_4ws_pub_
Command4ws command_struct_four_wheel_steering_
SpeedLimiter limiter_lin_
double wheel_radius_
Wheel radius (assuming it's the same for the left and right wheels):
SpeedLimiter limiter_ang_
std::string base_frame_id_
Frame to use for the robot base:
bool enable_odom_tf_
Whether to publish odometry to tf or not:
void updateOdometry(const ros::Time &time)
Update and publish odometry.
std::vector< hardware_interface::JointHandle > front_steering_joints_
CommandTwist command_struct_twist_
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):
void cmdFourWheelSteeringCallback(const four_wheel_steering_msgs::FourWheelSteering &command)
Velocity and steering command callback.
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.
std::shared_ptr< realtime_tools::RealtimePublisher< tf::tfMessage > > tf_odom_pub_
std::vector< hardware_interface::JointHandle > front_wheel_joints_
Hardware handles:
ros::Duration publish_period_
Odometry related:
ros::Subscriber sub_command_four_wheel_steering_
CommandTwist last1_cmd_
Speed limiters:
double wheel_steering_y_offset_
std::vector< hardware_interface::JointHandle > rear_steering_joints_
FourWheelSteeringController()
std::shared_ptr< realtime_tools::RealtimePublisher< nav_msgs::Odometry > > odom_pub_
Odometry related:
void updateCommand(const ros::Time &time, const ros::Duration &period)
Compute and publish command.
std::vector< hardware_interface::JointHandle > rear_wheel_joints_
bool enable_twist_cmd_
Whether the control is make with four_wheel_steering msg or twist msg:
void brake()
Brakes the wheels, i.e. sets the velocity to 0.
void update(const ros::Time &time, const ros::Duration &period)
Updates controller, i.e. computes the odometry and sets the new velocity commands.
ros::Subscriber sub_command_
realtime_tools::RealtimeBuffer< Command4ws > command_four_wheel_steering_
FourWheelSteering command related: