MobilityBasePlugin.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2014-2017, Dataspeed Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Dataspeed Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 #ifndef MOBILITY_BASE_PLUGIN_H_
00036 #define MOBILITY_BASE_PLUGIN_H_
00037 
00038 // Gazebo
00039 #include <gazebo/gazebo.hh>
00040 #include <gazebo/physics/physics.hh>
00041 #include <gazebo/common/common.hh>
00042 #include <gazebo/common/Plugin.hh>
00043 
00044 // ROS
00045 #include <ros/ros.h>
00046 #include <tf/transform_broadcaster.h>
00047 #include <gazebo_plugins/PubQueue.h>
00048 
00049 // ROS messages
00050 #include <mobility_base_core_msgs/BumperState.h>
00051 #include <mobility_base_core_msgs/Mode.h>
00052 #include <geometry_msgs/TwistStamped.h>
00053 #include <geometry_msgs/WrenchStamped.h>
00054 #include <sensor_msgs/JointState.h>
00055 #include <sensor_msgs/Imu.h>
00056 #include <sensor_msgs/MagneticField.h>
00057 #include <std_msgs/Bool.h>
00058 #include <std_msgs/Empty.h>
00059 #include <std_srvs/Empty.h>
00060 
00061 // Boost
00062 #include <boost/bind.hpp>
00063 #include <boost/thread/mutex.hpp>
00064 #include <boost/thread/lock_guard.hpp>
00065 
00066 #ifdef _CONST
00067 #undef _CONST
00068 #endif
00069 #if __cplusplus >= 201103L
00070 #define _CONST constexpr
00071 #else
00072 #define _CONST const
00073 #endif
00074 
00075 namespace gazebo
00076 {
00077 class MobilityBasePlugin : public ModelPlugin
00078 {
00079 public:
00080   MobilityBasePlugin();
00081   ~MobilityBasePlugin();
00082 
00083   static _CONST unsigned int NUM_WHEELS = 4;
00084   static _CONST unsigned int NUM_ROLLERS = 12;
00085   static _CONST double WHEEL_RADIUS = 8.0 / 2 * 0.0254;
00086   static _CONST double WHEEL_BASE_WIDTH = 0.680466;
00087   static _CONST double WHEEL_BASE_LENGTH = 0.505466;
00088   static _CONST double RADIANS_PER_SECOND_MAX = 14000 * (2.0 * M_PI / (200 * 48.5 / 2));
00089   static _CONST double CMD_TIMEOUT = 0.2;
00090   static _CONST double ACCEL_LIMIT_FAST_VXY = 4.0;
00091   static _CONST double ACCEL_LIMIT_FAST_WZ = 3.0 * M_PI;
00092   static _CONST double ACCEL_LIMIT_SLOW_VXY = 1.0;
00093   static _CONST double ACCEL_LIMIT_SLOW_WZ = 1.0 * M_PI;
00094   static _CONST double ACCEL_INSTANT_VXY = 0.5;
00095   static _CONST double ACCEL_INSTANT_WZ = 0.5 * M_PI;
00096   static _CONST double TORQUE_MAX_GLOBAL = 50.0;
00097   static _CONST double TORQUE_MAX_ALARM = 5.0;
00098 
00099   static _CONST double PUB_FREQ_VEHICLE = 250.0;
00100   static _CONST double PUB_FREQ_IMU = 100.0;
00101   static _CONST double PUB_FREQ_JOYSTICK = 50.0;
00102   static _CONST double PUB_FREQ_BUMPERS = 10.0;
00103   static _CONST double PUB_FREQ_MODE = 2.0;
00104 
00105   static _CONST double GAIN_X = 1.0;
00106   static _CONST double GAIN_Y = 1.0;
00107   static _CONST double GAIN_Z = 1.0;
00108 
00109   void Load(physics::ModelPtr _parent, sdf::ElementPtr sdf);
00110 
00111 protected:
00112   virtual void UpdateChild(const common::UpdateInfo & _info);
00113   virtual void FiniChild();
00114 
00115 private:
00116   // ROS callbacks
00117   void recvCmdVel(const geometry_msgs::Twist::ConstPtr& msg);
00118   void recvCmdVelRaw(const geometry_msgs::Twist::ConstPtr& msg);
00119   void recvSuppressWireless(const std_msgs::Empty::ConstPtr& msg);
00120 
00121   void publishMode(const ros::Time &stamp);
00122 
00123   // Gazebo
00124   event::ConnectionPtr update_connection_;
00125   physics::ModelPtr model_;
00126   physics::WorldPtr world_;
00127   physics::JointPtr joint_wheels_[NUM_WHEELS];
00128   physics::JointPtr joint_rollers_[NUM_WHEELS][NUM_ROLLERS];
00129   physics::LinkPtr link_base_footprint_;
00130   common::Time previous_stamp_;
00131   bool first_update_;
00132 
00133   // Command source cmd_vel
00134   math::Vector3 cmd_vel_;
00135   common::Time cmd_vel_stamp_;
00136   boost::mutex cmd_vel_mutex_;
00137 
00138   // Command source cmd_vel_raw
00139   math::Vector3 cmd_vel_raw_;
00140   common::Time cmd_vel_raw_stamp_;
00141   boost::mutex cmd_vel_raw_mutex_;
00142 
00143   // Drive control
00144   common::Time stamp_vehicle_;
00145   common::Time stamp_imu_;
00146   common::Time stamp_joystick_;
00147   common::Time stamp_bumpers_;
00148   common::Time stamp_mode_;
00149   math::Vector3 cmd_vel_history_;
00150   mobility_base_core_msgs::Mode::_mode_type mode_;
00151 
00152   // ROS
00153   ros::NodeHandle *nh_;
00154   tf::TransformBroadcaster *tf_broadcaster_;
00155   sensor_msgs::JointState joint_state_wheels_;
00156   sensor_msgs::JointState joint_state_rollers_;
00157 
00158   // ROS spin thread
00159   void spin();
00160   boost::thread *spinner_thread_;
00161 
00162   // Subscribed topics
00163   ros::Subscriber sub_cmd_vel_;
00164   ros::Subscriber sub_cmd_vel_raw_;
00165 
00166   // Published topics
00167   ros::Publisher pub_imu_data_;
00168   ros::Publisher pub_imu_is_calibrated_;
00169   ros::Publisher pub_imu_mag_;
00170   ros::Publisher pub_twist_;
00171   ros::Publisher pub_joystick_;
00172   ros::Publisher pub_wrench_;
00173   ros::Publisher pub_joint_states_;
00174   ros::Publisher pub_bumper_states_;
00175   ros::Publisher pub_mode_;
00176 
00177   // Publisher Queues
00178   PubMultiQueue pmq_;
00179   PubQueue<sensor_msgs::Imu>::Ptr pmq_imu_data_;
00180   PubQueue<std_msgs::Bool>::Ptr pmq_imu_is_calibrated_;
00181   PubQueue<sensor_msgs::MagneticField>::Ptr pmq_imu_mag_;
00182   PubQueue<geometry_msgs::TwistStamped>::Ptr pmq_twist_;
00183   PubQueue<geometry_msgs::TwistStamped>::Ptr pmq_joystick_;
00184   PubQueue<geometry_msgs::WrenchStamped>::Ptr pmq_wrench_;
00185   PubQueue<sensor_msgs::JointState>::Ptr pmq_joint_states_;
00186   PubQueue<mobility_base_core_msgs::BumperState>::Ptr pmq_bumper_states_;
00187   PubQueue<mobility_base_core_msgs::Mode>::Ptr pmq_mode_;
00188 
00189   // Calculated constant parameters
00190   double omni_a_;
00191   double omni_b_;
00192   double omni_c_;
00193   const char *frame_id_;
00194 
00195   // Parameters
00196   bool fast_;
00197   std::string parent_frame_id_;
00198   std::string child_frame_id_;
00199 
00200 
00201   void omniFromCartesian(double vx, double vy, double wz, double w[4]) const;
00202   void omniToCartesian(const double w[4], double *vx, double *vy, double *wz) const;
00203   static inline bool omniSaturate(double limit, double speeds[4])
00204   {
00205       unsigned int i;
00206       limit = fabs(limit);
00207       double max = 0;
00208       double val;
00209       for (i = 0; i < 4; i++) {
00210           val = fabs(speeds[i]);
00211           if (val > max) {
00212               max = val;
00213           }
00214       }
00215       if (max > limit) {
00216           val = limit / max;
00217           for (i = 0; i < 4; i++) {
00218               speeds[i] *= val;
00219           }
00220           return true;
00221       }
00222       return false;
00223   }
00224   static inline double limitDelta(double input, double previous, double limit)
00225   {
00226     limit = fabs(limit);
00227     double delta = input - previous;
00228     if (delta > limit) {
00229         delta = limit;
00230     }
00231     if (delta < -limit) {
00232         delta = -limit;
00233     }
00234     return previous + delta;
00235   }
00236 
00237 };
00238 } //namespace gazebo
00239 
00240 #undef _CONST
00241 
00242 #endif /* MOBILITY_BASE_PLUGIN_H_ */


mobility_base_gazebo_plugins
Author(s): Dataspeed Inc.
autogenerated on Thu Jun 6 2019 20:44:12