35 #ifndef MOBILITY_BASE_PLUGIN_H_ 36 #define MOBILITY_BASE_PLUGIN_H_ 39 #include <gazebo/gazebo.hh> 40 #include <gazebo/physics/physics.hh> 41 #include <gazebo/common/common.hh> 42 #include <gazebo/common/Plugin.hh> 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> 62 #include <boost/bind.hpp> 63 #include <boost/thread/mutex.hpp> 64 #include <boost/thread/lock_guard.hpp> 69 #if __cplusplus >= 201103L 70 #define _CONST constexpr 109 void Load(physics::ModelPtr _parent, sdf::ElementPtr sdf);
112 virtual void UpdateChild(
const common::UpdateInfo & _info);
117 void recvCmdVel(
const geometry_msgs::Twist::ConstPtr& msg);
118 void recvCmdVelRaw(
const geometry_msgs::Twist::ConstPtr& msg);
150 mobility_base_core_msgs::Mode::_mode_type
mode_;
202 void omniToCartesian(
const double w[4],
double *vx,
double *vy,
double *wz)
const;
209 for (i = 0; i < 4; i++) {
210 val = fabs(speeds[i]);
217 for (i = 0; i < 4; i++) {
224 static inline double limitDelta(
double input,
double previous,
double limit)
227 double delta = input - previous;
231 if (delta < -limit) {
234 return previous + delta;
static _CONST double PUB_FREQ_BUMPERS
void recvCmdVel(const geometry_msgs::Twist::ConstPtr &msg)
ros::Publisher pub_bumper_states_
physics::JointPtr joint_wheels_[NUM_WHEELS]
ros::Publisher pub_imu_is_calibrated_
common::Time cmd_vel_stamp_
static _CONST double GAIN_X
ros::Publisher pub_imu_data_
std::string child_frame_id_
physics::JointPtr joint_rollers_[NUM_WHEELS][NUM_ROLLERS]
PubQueue< geometry_msgs::TwistStamped >::Ptr pmq_joystick_
math::Vector3 cmd_vel_history_
boost::mutex cmd_vel_raw_mutex_
ros::Publisher pub_twist_
static _CONST unsigned int NUM_ROLLERS
void recvCmdVelRaw(const geometry_msgs::Twist::ConstPtr &msg)
ros::Subscriber sub_cmd_vel_
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
common::Time previous_stamp_
event::ConnectionPtr update_connection_
common::Time stamp_joystick_
static _CONST double PUB_FREQ_JOYSTICK
PubQueue< std_msgs::Bool >::Ptr pmq_imu_is_calibrated_
physics::LinkPtr link_base_footprint_
common::Time stamp_bumpers_
static _CONST double ACCEL_LIMIT_SLOW_WZ
math::Vector3 cmd_vel_raw_
static _CONST double ACCEL_LIMIT_SLOW_VXY
ros::Publisher pub_joystick_
static _CONST double ACCEL_LIMIT_FAST_VXY
static bool omniSaturate(double limit, double speeds[4])
static _CONST double CMD_TIMEOUT
ros::Publisher pub_joint_states_
void omniFromCartesian(double vx, double vy, double wz, double w[4]) const
common::Time cmd_vel_raw_stamp_
PubQueue< sensor_msgs::MagneticField >::Ptr pmq_imu_mag_
static _CONST double WHEEL_RADIUS
boost::thread * spinner_thread_
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_
boost::mutex cmd_vel_mutex_
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
ros::Subscriber sub_cmd_vel_raw_
static _CONST double WHEEL_BASE_WIDTH
mobility_base_core_msgs::Mode::_mode_type mode_
ros::Publisher pub_wrench_
common::Time stamp_vehicle_
virtual void UpdateChild(const common::UpdateInfo &_info)
void recvSuppressWireless(const std_msgs::Empty::ConstPtr &msg)
std::string parent_frame_id_
void publishMode(const ros::Time &stamp)
tf::TransformBroadcaster * tf_broadcaster_
ros::Publisher pub_imu_mag_
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)