ackermann_controller.h
Go to the documentation of this file.
1 
6 #ifndef ACKERMANN_CONTROLLER_H
7 #define ACKERMANN_CONTROLLER_H
8 
12 
13 #include <nav_msgs/Odometry.h>
14 #include <tf/tfMessage.h>
15 
18 
22 
24 
26  hardware_interface::VelocityJointInterface,
27  hardware_interface::JointStateInterface,
28  hardware_interface::PositionJointInterface>
29 {
30 public:
31 
33 
40  bool init(
42  ros::NodeHandle& root_nh,
43  ros::NodeHandle &controller_nh);
44 
50  void update(const ros::Time& time, const ros::Duration& period);
51 
56  void starting(const ros::Time& time);
57 
62  void stopping(const ros::Time& /*time*/);
63 
64 private:
65 
66  std::string name_;
67 
70  bool open_loop_;
71 
72  std::vector<ActuatedWheel> spinning_joints_;
73  std::vector<Wheel> odometry_joints_;
74  std::vector<ActuatedJoint> steering_joints_;
75 
76  struct Commands
77  {
78  double lin;
79  double ang;
81 
82  Commands() : lin(0.0), ang(0.0), stamp(0.0) {}
83  };
84 
88 
92 
94  double wheelbase_;
97  std::string odom_frame_id_;
98  std::string base_frame_id_;
99  std::string base_link_;
101 
105 
106 
107 private:
108 
109  void brake();
110 
111  void cmdVelCallback(const geometry_msgs::Twist& command);
112 
113  bool initParams(ros::NodeHandle& controller_nh);
114 
115  void updateOdometry(const ros::Time& time, const ros::Duration& period);
116 
117  void moveRobot(const ros::Time& time, const ros::Duration& period);
118 
120 
121  std::vector<std::string> getJointNames(ros::NodeHandle& controller_nh, const std::string& param);
122 
123  void setOdomPubFields(ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh);
124 
125 };
126 }
127 
128 #endif
void stopping(const ros::Time &)
Stops controller.
void updateOdometry(const ros::Time &time, const ros::Duration &period)
std::vector< ActuatedJoint > steering_joints_
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_
void cmdVelCallback(const geometry_msgs::Twist &command)
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)
ackermann_controller::Odometry odometry_
std::vector< std::string > getJointNames(ros::NodeHandle &controller_nh, const std::string &param)
The Odometry class handles odometry readings (2D pose and velocity with related timestamp) ...
Definition: odometry.h:27


ackermann_controller
Author(s): GĂ©rald Lelong
autogenerated on Mon Jun 10 2019 12:44:48