6 #ifndef ACKERMANN_CONTROLLER_H 7 #define ACKERMANN_CONTROLLER_H 13 #include <nav_msgs/Odometry.h> 14 #include <tf/tfMessage.h> 26 hardware_interface::VelocityJointInterface,
27 hardware_interface::JointStateInterface,
28 hardware_interface::PositionJointInterface>
std::vector< Wheel > odometry_joints_
void stopping(const ros::Time &)
Stops controller.
void updateOdometry(const ros::Time &time, const ros::Duration &period)
std::vector< ActuatedJoint > steering_joints_
ros::Subscriber sub_command_
std::vector< ActuatedWheel > spinning_joints_
boost::shared_ptr< realtime_tools::RealtimePublisher< nav_msgs::Odometry > > odom_pub_
boost::shared_ptr< realtime_tools::RealtimePublisher< tf::tfMessage > > tf_odom_pub_
bool steering_angle_instead_of_angular_speed_
void cmdVelCallback(const geometry_msgs::Twist &command)
ros::Duration publish_period_
ros::Time last_state_publish_time_
bool initParams(ros::NodeHandle &controller_nh)
void setOdomPubFields(ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
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.
ackermann_controller::SpeedLimiter limiter_
boost::shared_ptr< urdf::ModelInterface > getURDFModel(const ros::NodeHandle &nh)
bool init(hardware_interface::RobotHW *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Initialize controller.
realtime_tools::RealtimeBuffer< Commands > command_
void moveRobot(const ros::Time &time, const ros::Duration &period)
std::string base_frame_id_
ackermann_controller::Odometry odometry_
std::string odom_frame_id_
int velocity_rolling_window_size_
std::vector< std::string > getJointNames(ros::NodeHandle &controller_nh, const std::string ¶m)
The Odometry class handles odometry readings (2D pose and velocity with related timestamp) ...