four_wheel_steering_controller.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, Irstea
5  * Copyright (c) 2013, PAL Robotics, S.L.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Irstea nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 #pragma once
37 
38 
42 
43 #include <nav_msgs/Odometry.h>
44 #include <four_wheel_steering_msgs/FourWheelSteeringStamped.h>
45 #include <tf/tfMessage.h>
46 
49 
52 
54 
65  : public controller_interface::MultiInterfaceController<hardware_interface::VelocityJointInterface,
66  hardware_interface::PositionJointInterface>
67  {
68  public:
70 
77  bool init(hardware_interface::RobotHW* robot_hw,
78  ros::NodeHandle& root_nh,
79  ros::NodeHandle &controller_nh);
80 
86  void update(const ros::Time& time, const ros::Duration& period);
87 
92  void starting(const ros::Time& time);
93 
98  void stopping(const ros::Time& /*time*/);
99 
100  private:
101  std::string name_;
102 
107 
109  std::vector<hardware_interface::JointHandle> front_wheel_joints_;
110  std::vector<hardware_interface::JointHandle> rear_wheel_joints_;
111  std::vector<hardware_interface::JointHandle> front_steering_joints_;
112  std::vector<hardware_interface::JointHandle> rear_steering_joints_;
113 
115  struct Command
116  {
118 
119  Command() : stamp(0.0) {}
120  };
122  {
123  double lin_x;
124  double lin_y;
125  double ang;
126 
127  CommandTwist() : lin_x(0.0), lin_y(0.0), ang(0.0) {}
128  };
130  {
131  double lin;
134 
135  Command4ws() : lin(0.0), front_steering(0.0), rear_steering(0.0) {}
136  };
140 
145 
147  std::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::Odometry> > odom_pub_;
148  std::shared_ptr<realtime_tools::RealtimePublisher<four_wheel_steering_msgs::FourWheelSteeringStamped> > odom_4ws_pub_;
149  std::shared_ptr<realtime_tools::RealtimePublisher<tf::tfMessage> > tf_odom_pub_;
151 
153  double track_;
157 
160 
162  double wheel_base_;
163 
166 
168  std::string base_frame_id_;
169 
172 
175 
181 
182  private:
183 
188  void updateOdometry(const ros::Time &time);
194  void updateCommand(const ros::Time& time, const ros::Duration& period);
195 
199  void brake();
200 
205  void cmdVelCallback(const geometry_msgs::Twist& command);
206 
211  void cmdFourWheelSteeringCallback(const four_wheel_steering_msgs::FourWheelSteering &command);
212 
221  bool getWheelNames(ros::NodeHandle& controller_nh,
222  const std::string& wheel_param,
223  std::vector<std::string>& wheel_names);
224 
230  void setOdomPubFields(ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh);
231 
232  };
233 
235 } // namespace four_wheel_steering_controller
double cmd_vel_timeout_
Timeout to consider cmd_vel commands old:
void cmdVelCallback(const geometry_msgs::Twist &command)
Velocity command callback.
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.
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) ...
Definition: odometry.h:52
bool enable_twist_cmd_
Whether the control is make with four_wheel_steering msg or twist msg:
double wheel_radius_
Wheel radius (assuming it&#39;s the same for the left and right wheels):
std::shared_ptr< realtime_tools::RealtimePublisher< nav_msgs::Odometry > > odom_pub_
Odometry related:
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.
std::shared_ptr< realtime_tools::RealtimePublisher< four_wheel_steering_msgs::FourWheelSteeringStamped > > odom_4ws_pub_
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)
void brake()
Brakes the wheels, i.e. sets the velocity to 0.
std::shared_ptr< realtime_tools::RealtimePublisher< tf::tfMessage > > tf_odom_pub_
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:


four_wheel_steering_controller
Author(s): Vincent Rousseau
autogenerated on Fri Feb 3 2023 03:19:10