MobilityBasePlugin.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2014-2017, Dataspeed Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Dataspeed Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #ifndef MOBILITY_BASE_PLUGIN_H_
36 #define MOBILITY_BASE_PLUGIN_H_
37 
38 // Gazebo
39 #include <gazebo/gazebo.hh>
40 #include <gazebo/physics/physics.hh>
41 #include <gazebo/common/common.hh>
42 #include <gazebo/common/Plugin.hh>
43 
44 // ROS
45 #include <ros/ros.h>
48 
49 // ROS messages
50 #include <mobility_base_core_msgs/BumperState.h>
51 #include <mobility_base_core_msgs/Mode.h>
52 #include <geometry_msgs/TwistStamped.h>
53 #include <geometry_msgs/WrenchStamped.h>
54 #include <sensor_msgs/JointState.h>
55 #include <sensor_msgs/Imu.h>
56 #include <sensor_msgs/MagneticField.h>
57 #include <std_msgs/Bool.h>
58 #include <std_msgs/Empty.h>
59 #include <std_srvs/Empty.h>
60 
61 // Boost
62 #include <boost/bind.hpp>
63 #include <boost/thread/mutex.hpp>
64 #include <boost/thread/lock_guard.hpp>
65 
66 #ifdef _CONST
67 #undef _CONST
68 #endif
69 #if __cplusplus >= 201103L
70 #define _CONST constexpr
71 #else
72 #define _CONST const
73 #endif
74 
75 namespace gazebo
76 {
77 class MobilityBasePlugin : public ModelPlugin
78 {
79 public:
82 
83  static _CONST unsigned int NUM_WHEELS = 4;
84  static _CONST unsigned int NUM_ROLLERS = 12;
85  static _CONST double WHEEL_RADIUS = 8.0 / 2 * 0.0254;
86  static _CONST double WHEEL_BASE_WIDTH = 0.680466;
87  static _CONST double WHEEL_BASE_LENGTH = 0.505466;
88  static _CONST double RADIANS_PER_SECOND_MAX = 14000 * (2.0 * M_PI / (200 * 48.5 / 2));
89  static _CONST double CMD_TIMEOUT = 0.2;
90  static _CONST double ACCEL_LIMIT_FAST_VXY = 4.0;
91  static _CONST double ACCEL_LIMIT_FAST_WZ = 3.0 * M_PI;
92  static _CONST double ACCEL_LIMIT_SLOW_VXY = 1.0;
93  static _CONST double ACCEL_LIMIT_SLOW_WZ = 1.0 * M_PI;
94  static _CONST double ACCEL_INSTANT_VXY = 0.5;
95  static _CONST double ACCEL_INSTANT_WZ = 0.5 * M_PI;
96  static _CONST double TORQUE_MAX_GLOBAL = 50.0;
97  static _CONST double TORQUE_MAX_ALARM = 5.0;
98 
99  static _CONST double PUB_FREQ_VEHICLE = 250.0;
100  static _CONST double PUB_FREQ_IMU = 100.0;
101  static _CONST double PUB_FREQ_JOYSTICK = 50.0;
102  static _CONST double PUB_FREQ_BUMPERS = 10.0;
103  static _CONST double PUB_FREQ_MODE = 2.0;
104 
105  static _CONST double GAIN_X = 1.0;
106  static _CONST double GAIN_Y = 1.0;
107  static _CONST double GAIN_Z = 1.0;
108 
109  void Load(physics::ModelPtr _parent, sdf::ElementPtr sdf);
110 
111 protected:
112  virtual void UpdateChild(const common::UpdateInfo & _info);
113  virtual void FiniChild();
114 
115 private:
116  // ROS callbacks
117  void recvCmdVel(const geometry_msgs::Twist::ConstPtr& msg);
118  void recvCmdVelRaw(const geometry_msgs::Twist::ConstPtr& msg);
119  void recvSuppressWireless(const std_msgs::Empty::ConstPtr& msg);
120 
121  void publishMode(const ros::Time &stamp);
122 
123  // Gazebo
124  event::ConnectionPtr update_connection_;
125  physics::ModelPtr model_;
126  physics::WorldPtr world_;
127  physics::JointPtr joint_wheels_[NUM_WHEELS];
128  physics::JointPtr joint_rollers_[NUM_WHEELS][NUM_ROLLERS];
129  physics::LinkPtr link_base_footprint_;
130  common::Time previous_stamp_;
132 
133  // Command source cmd_vel
134  math::Vector3 cmd_vel_;
135  common::Time cmd_vel_stamp_;
136  boost::mutex cmd_vel_mutex_;
137 
138  // Command source cmd_vel_raw
139  math::Vector3 cmd_vel_raw_;
140  common::Time cmd_vel_raw_stamp_;
141  boost::mutex cmd_vel_raw_mutex_;
142 
143  // Drive control
144  common::Time stamp_vehicle_;
145  common::Time stamp_imu_;
146  common::Time stamp_joystick_;
147  common::Time stamp_bumpers_;
148  common::Time stamp_mode_;
149  math::Vector3 cmd_vel_history_;
150  mobility_base_core_msgs::Mode::_mode_type mode_;
151 
152  // ROS
155  sensor_msgs::JointState joint_state_wheels_;
156  sensor_msgs::JointState joint_state_rollers_;
157 
158  // ROS spin thread
159  void spin();
160  boost::thread *spinner_thread_;
161 
162  // Subscribed topics
165 
166  // Published topics
176 
177  // Publisher Queues
188 
189  // Calculated constant parameters
190  double omni_a_;
191  double omni_b_;
192  double omni_c_;
193  const char *frame_id_;
194 
195  // Parameters
196  bool fast_;
197  std::string parent_frame_id_;
198  std::string child_frame_id_;
199 
200 
201  void omniFromCartesian(double vx, double vy, double wz, double w[4]) const;
202  void omniToCartesian(const double w[4], double *vx, double *vy, double *wz) const;
203  static inline bool omniSaturate(double limit, double speeds[4])
204  {
205  unsigned int i;
206  limit = fabs(limit);
207  double max = 0;
208  double val;
209  for (i = 0; i < 4; i++) {
210  val = fabs(speeds[i]);
211  if (val > max) {
212  max = val;
213  }
214  }
215  if (max > limit) {
216  val = limit / max;
217  for (i = 0; i < 4; i++) {
218  speeds[i] *= val;
219  }
220  return true;
221  }
222  return false;
223  }
224  static inline double limitDelta(double input, double previous, double limit)
225  {
226  limit = fabs(limit);
227  double delta = input - previous;
228  if (delta > limit) {
229  delta = limit;
230  }
231  if (delta < -limit) {
232  delta = -limit;
233  }
234  return previous + delta;
235  }
236 
237 };
238 } //namespace gazebo
239 
240 #undef _CONST
241 
242 #endif /* MOBILITY_BASE_PLUGIN_H_ */
static _CONST double PUB_FREQ_BUMPERS
void recvCmdVel(const geometry_msgs::Twist::ConstPtr &msg)
physics::JointPtr joint_wheels_[NUM_WHEELS]
static _CONST double GAIN_X
physics::JointPtr joint_rollers_[NUM_WHEELS][NUM_ROLLERS]
PubQueue< geometry_msgs::TwistStamped >::Ptr pmq_joystick_
static _CONST unsigned int NUM_ROLLERS
void recvCmdVelRaw(const geometry_msgs::Twist::ConstPtr &msg)
void Load(physics::ModelPtr _parent, sdf::ElementPtr sdf)
static _CONST double ACCEL_INSTANT_VXY
static _CONST double GAIN_Y
static _CONST double ACCEL_LIMIT_FAST_WZ
static _CONST double ACCEL_INSTANT_WZ
event::ConnectionPtr update_connection_
static _CONST double PUB_FREQ_JOYSTICK
PubQueue< std_msgs::Bool >::Ptr pmq_imu_is_calibrated_
physics::LinkPtr link_base_footprint_
static _CONST double ACCEL_LIMIT_SLOW_WZ
static _CONST double ACCEL_LIMIT_SLOW_VXY
static _CONST double ACCEL_LIMIT_FAST_VXY
static bool omniSaturate(double limit, double speeds[4])
static _CONST double CMD_TIMEOUT
void omniFromCartesian(double vx, double vy, double wz, double w[4]) const
PubQueue< sensor_msgs::MagneticField >::Ptr pmq_imu_mag_
static _CONST double WHEEL_RADIUS
static _CONST double TORQUE_MAX_ALARM
sensor_msgs::JointState joint_state_rollers_
static _CONST double PUB_FREQ_IMU
PubQueue< mobility_base_core_msgs::BumperState >::Ptr pmq_bumper_states_
PubQueue< sensor_msgs::Imu >::Ptr pmq_imu_data_
PubQueue< sensor_msgs::JointState >::Ptr pmq_joint_states_
void omniToCartesian(const double w[4], double *vx, double *vy, double *wz) const
static _CONST double TORQUE_MAX_GLOBAL
static _CONST double WHEEL_BASE_LENGTH
static _CONST double PUB_FREQ_MODE
static _CONST double GAIN_Z
PubQueue< geometry_msgs::TwistStamped >::Ptr pmq_twist_
static _CONST unsigned int NUM_WHEELS
static _CONST double WHEEL_BASE_WIDTH
mobility_base_core_msgs::Mode::_mode_type mode_
#define _CONST
virtual void UpdateChild(const common::UpdateInfo &_info)
void recvSuppressWireless(const std_msgs::Empty::ConstPtr &msg)
void publishMode(const ros::Time &stamp)
tf::TransformBroadcaster * tf_broadcaster_
sensor_msgs::JointState joint_state_wheels_
PubQueue< geometry_msgs::WrenchStamped >::Ptr pmq_wrench_
static _CONST double RADIANS_PER_SECOND_MAX
PubQueue< mobility_base_core_msgs::Mode >::Ptr pmq_mode_
static _CONST double PUB_FREQ_VEHICLE
static double limitDelta(double input, double previous, double limit)


mobility_base_gazebo_plugins
Author(s): Dataspeed Inc.
autogenerated on Sun Oct 6 2019 03:32:29