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 
41 
42 #include <nav_msgs/Odometry.h>
43 #include <four_wheel_steering_msgs/FourWheelSteeringStamped.h>
44 #include <tf/tfMessage.h>
45 
48 
51 
53 
64  : public controller_interface::MultiInterfaceController<hardware_interface::VelocityJointInterface,
65  hardware_interface::PositionJointInterface>
66  {
67  public:
69 
76  bool init(hardware_interface::RobotHW* robot_hw,
77  ros::NodeHandle& root_nh,
78  ros::NodeHandle &controller_nh);
79 
85  void update(const ros::Time& time, const ros::Duration& period);
86 
91  void starting(const ros::Time& time);
92 
97  void stopping(const ros::Time& /*time*/);
98 
99  private:
100  std::string name_;
101 
105  bool open_loop_;
106 
108  std::vector<hardware_interface::JointHandle> front_wheel_joints_;
109  std::vector<hardware_interface::JointHandle> rear_wheel_joints_;
110  std::vector<hardware_interface::JointHandle> front_steering_joints_;
111  std::vector<hardware_interface::JointHandle> rear_steering_joints_;
112 
114  struct Command
115  {
117 
118  Command() : stamp(0.0) {}
119  };
120  struct CommandTwist : Command
121  {
122  double lin_x;
123  double lin_y;
124  double ang;
125 
126  CommandTwist() : lin_x(0.0), lin_y(0.0), ang(0.0) {}
127  };
128  struct Command4ws : Command
129  {
130  double lin;
131  double front_steering;
132  double rear_steering;
133 
134  Command4ws() : lin(0.0), front_steering(0.0), rear_steering(0.0) {}
135  };
137  CommandTwist command_struct_twist_;
139 
144 
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_;
150 
152  double track_;
156 
158  double wheel_radius_;
159 
161  double wheel_base_;
162 
164  double cmd_vel_timeout_;
165 
167  std::string base_frame_id_;
168 
171 
173  bool enable_twist_cmd_;
174 
180 
181  private:
182 
187  void updateOdometry(const ros::Time &time);
193  void updateCommand(const ros::Time& time, const ros::Duration& period);
194 
198  void brake();
199 
204  void cmdVelCallback(const geometry_msgs::Twist& command);
205 
210  void cmdFourWheelSteeringCallback(const four_wheel_steering_msgs::FourWheelSteering &command);
211 
220  bool getWheelNames(ros::NodeHandle& controller_nh,
221  const std::string& wheel_param,
222  std::vector<std::string>& wheel_names);
223 
229  void setOdomPubFields(ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh);
230 
231  };
232 
233 } // namespace four_wheel_steering_controller
realtime_tools::RealtimeBuffer
four_wheel_steering_controller::FourWheelSteeringController::open_loop_
bool open_loop_
Definition: four_wheel_steering_controller.h:171
four_wheel_steering_controller::FourWheelSteeringController::name_
std::string name_
Definition: four_wheel_steering_controller.h:166
four_wheel_steering_controller::FourWheelSteeringController::Command4ws::lin
double lin
Definition: four_wheel_steering_controller.h:196
realtime_publisher.h
four_wheel_steering_controller::FourWheelSteeringController::init
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Initialize controller.
Definition: four_wheel_steering_controller.cpp:91
four_wheel_steering_controller::FourWheelSteeringController::stopping
void stopping(const ros::Time &)
Stops controller.
Definition: four_wheel_steering_controller.cpp:281
four_wheel_steering_controller::FourWheelSteeringController::last0_cmd_
CommandTwist last0_cmd_
Definition: four_wheel_steering_controller.h:243
four_wheel_steering_controller::SpeedLimiter
Definition: speed_limiter.h:83
four_wheel_steering_controller::FourWheelSteeringController::last_state_publish_time_
ros::Time last_state_publish_time_
Definition: four_wheel_steering_controller.h:170
four_wheel_steering_controller::FourWheelSteeringController::starting
void starting(const ros::Time &time)
Starts controller.
Definition: four_wheel_steering_controller.cpp:271
four_wheel_steering_controller::FourWheelSteeringController::Command::stamp
ros::Time stamp
Definition: four_wheel_steering_controller.h:182
realtime_buffer.h
four_wheel_steering_controller::FourWheelSteeringController::cmd_vel_timeout_
double cmd_vel_timeout_
Timeout to consider cmd_vel commands old:
Definition: four_wheel_steering_controller.h:230
four_wheel_steering_controller::FourWheelSteeringController::setOdomPubFields
void setOdomPubFields(ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Sets the odometry publishing fields.
Definition: four_wheel_steering_controller.cpp:657
four_wheel_steering_controller::Odometry
The Odometry class handles odometry readings (2D pose and velocity with related timestamp)
Definition: odometry.h:84
four_wheel_steering_controller::FourWheelSteeringController::command_twist_
realtime_tools::RealtimeBuffer< CommandTwist > command_twist_
Definition: four_wheel_steering_controller.h:202
four_wheel_steering_controller::FourWheelSteeringController::Command4ws::rear_steering
double rear_steering
Definition: four_wheel_steering_controller.h:198
four_wheel_steering_controller::FourWheelSteeringController::cmdVelCallback
void cmdVelCallback(const geometry_msgs::Twist &command)
Velocity command callback.
Definition: four_wheel_steering_controller.cpp:549
four_wheel_steering_controller::FourWheelSteeringController::Command4ws::front_steering
double front_steering
Definition: four_wheel_steering_controller.h:197
four_wheel_steering_controller::FourWheelSteeringController::odom_4ws_pub_
std::shared_ptr< realtime_tools::RealtimePublisher< four_wheel_steering_msgs::FourWheelSteeringStamped > > odom_4ws_pub_
Definition: four_wheel_steering_controller.h:213
four_wheel_steering_controller::FourWheelSteeringController::command_struct_four_wheel_steering_
Command4ws command_struct_four_wheel_steering_
Definition: four_wheel_steering_controller.h:208
odometry.h
four_wheel_steering_controller::FourWheelSteeringController::CommandTwist::ang
double ang
Definition: four_wheel_steering_controller.h:190
four_wheel_steering_controller::FourWheelSteeringController::limiter_lin_
SpeedLimiter limiter_lin_
Definition: four_wheel_steering_controller.h:244
four_wheel_steering_controller::FourWheelSteeringController::wheel_radius_
double wheel_radius_
Wheel radius (assuming it's the same for the left and right wheels):
Definition: four_wheel_steering_controller.h:224
four_wheel_steering_controller::FourWheelSteeringController::limiter_ang_
SpeedLimiter limiter_ang_
Definition: four_wheel_steering_controller.h:245
four_wheel_steering_controller::FourWheelSteeringController::CommandTwist
Definition: four_wheel_steering_controller.h:186
four_wheel_steering_controller::FourWheelSteeringController::base_frame_id_
std::string base_frame_id_
Frame to use for the robot base:
Definition: four_wheel_steering_controller.h:233
four_wheel_steering_controller::FourWheelSteeringController::enable_odom_tf_
bool enable_odom_tf_
Whether to publish odometry to tf or not:
Definition: four_wheel_steering_controller.h:236
four_wheel_steering_controller::FourWheelSteeringController::updateOdometry
void updateOdometry(const ros::Time &time)
Update and publish odometry.
Definition: four_wheel_steering_controller.cpp:286
four_wheel_steering_controller::FourWheelSteeringController::front_steering_joints_
std::vector< hardware_interface::JointHandle > front_steering_joints_
Definition: four_wheel_steering_controller.h:176
joint_command_interface.h
hardware_interface::RobotHW
controller_interface::MultiInterfaceController
four_wheel_steering_controller::FourWheelSteeringController::command_struct_twist_
CommandTwist command_struct_twist_
Definition: four_wheel_steering_controller.h:203
four_wheel_steering_controller::FourWheelSteeringController::Command4ws::Command4ws
Command4ws()
Definition: four_wheel_steering_controller.h:200
four_wheel_steering_controller::FourWheelSteeringController::track_
double track_
Wheel separation (or track), distance between left and right wheels (from the midpoint of the wheel w...
Definition: four_wheel_steering_controller.h:218
four_wheel_steering_controller::FourWheelSteeringController
Definition: four_wheel_steering_controller.h:96
four_wheel_steering_controller::FourWheelSteeringController::wheel_base_
double wheel_base_
Wheel base (distance between front and rear wheel):
Definition: four_wheel_steering_controller.h:227
four_wheel_steering_controller::FourWheelSteeringController::cmdFourWheelSteeringCallback
void cmdFourWheelSteeringCallback(const four_wheel_steering_msgs::FourWheelSteering &command)
Velocity and steering command callback.
Definition: four_wheel_steering_controller.cpp:576
four_wheel_steering_controller::FourWheelSteeringController::getWheelNames
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.
Definition: four_wheel_steering_controller.cpp:604
four_wheel_steering_controller::FourWheelSteeringController::Command::Command
Command()
Definition: four_wheel_steering_controller.h:184
four_wheel_steering_controller::FourWheelSteeringController::tf_odom_pub_
std::shared_ptr< realtime_tools::RealtimePublisher< tf::tfMessage > > tf_odom_pub_
Definition: four_wheel_steering_controller.h:214
four_wheel_steering_controller::FourWheelSteeringController::front_wheel_joints_
std::vector< hardware_interface::JointHandle > front_wheel_joints_
Hardware handles:
Definition: four_wheel_steering_controller.h:174
four_wheel_steering_controller::FourWheelSteeringController::odometry_
Odometry odometry_
Definition: four_wheel_steering_controller.h:215
four_wheel_steering_controller::FourWheelSteeringController::publish_period_
ros::Duration publish_period_
Odometry related:
Definition: four_wheel_steering_controller.h:169
four_wheel_steering_controller::FourWheelSteeringController::sub_command_four_wheel_steering_
ros::Subscriber sub_command_four_wheel_steering_
Definition: four_wheel_steering_controller.h:209
four_wheel_steering_controller
Definition: four_wheel_steering_controller.h:52
four_wheel_steering_controller::FourWheelSteeringController::last1_cmd_
CommandTwist last1_cmd_
Speed limiters:
Definition: four_wheel_steering_controller.h:242
four_wheel_steering_controller::FourWheelSteeringController::wheel_steering_y_offset_
double wheel_steering_y_offset_
Definition: four_wheel_steering_controller.h:221
four_wheel_steering_controller::FourWheelSteeringController::rear_steering_joints_
std::vector< hardware_interface::JointHandle > rear_steering_joints_
Definition: four_wheel_steering_controller.h:177
ros::Time
four_wheel_steering_controller::FourWheelSteeringController::FourWheelSteeringController
FourWheelSteeringController()
Definition: four_wheel_steering_controller.cpp:77
four_wheel_steering_controller::FourWheelSteeringController::odom_pub_
std::shared_ptr< realtime_tools::RealtimePublisher< nav_msgs::Odometry > > odom_pub_
Odometry related:
Definition: four_wheel_steering_controller.h:212
four_wheel_steering_controller::FourWheelSteeringController::updateCommand
void updateCommand(const ros::Time &time, const ros::Duration &period)
Compute and publish command.
Definition: four_wheel_steering_controller.cpp:368
speed_limiter.h
four_wheel_steering_controller::FourWheelSteeringController::CommandTwist::CommandTwist
CommandTwist()
Definition: four_wheel_steering_controller.h:192
four_wheel_steering_controller::FourWheelSteeringController::rear_wheel_joints_
std::vector< hardware_interface::JointHandle > rear_wheel_joints_
Definition: four_wheel_steering_controller.h:175
four_wheel_steering_controller::FourWheelSteeringController::CommandTwist::lin_y
double lin_y
Definition: four_wheel_steering_controller.h:189
four_wheel_steering_controller::FourWheelSteeringController::enable_twist_cmd_
bool enable_twist_cmd_
Whether the control is make with four_wheel_steering msg or twist msg:
Definition: four_wheel_steering_controller.h:239
ros::Duration
four_wheel_steering_controller::FourWheelSteeringController::brake
void brake()
Brakes the wheels, i.e. sets the velocity to 0.
Definition: four_wheel_steering_controller.cpp:532
four_wheel_steering_controller::FourWheelSteeringController::update
void update(const ros::Time &time, const ros::Duration &period)
Updates controller, i.e. computes the odometry and sets the new velocity commands.
Definition: four_wheel_steering_controller.cpp:265
ros::NodeHandle
ros::Subscriber
four_wheel_steering_controller::FourWheelSteeringController::sub_command_
ros::Subscriber sub_command_
Definition: four_wheel_steering_controller.h:204
four_wheel_steering_controller::FourWheelSteeringController::command_four_wheel_steering_
realtime_tools::RealtimeBuffer< Command4ws > command_four_wheel_steering_
FourWheelSteering command related:
Definition: four_wheel_steering_controller.h:207
four_wheel_steering_controller::FourWheelSteeringController::CommandTwist::lin_x
double lin_x
Definition: four_wheel_steering_controller.h:188
multi_interface_controller.h


four_wheel_steering_controller
Author(s): Vincent Rousseau
autogenerated on Fri May 24 2024 02:41:15