Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023 #ifndef ROTORS_GAZEBO_PLUGINS_GAZEBO_MULTIROTOR_BASE_PLUGIN_H
00024 #define ROTORS_GAZEBO_PLUGINS_GAZEBO_MULTIROTOR_BASE_PLUGIN_H
00025
00026 #include <string>
00027
00028 #include <gazebo/common/common.hh>
00029 #include <gazebo/common/Plugin.hh>
00030 #include <gazebo/gazebo.hh>
00031 #include <gazebo/physics/physics.hh>
00032
00033 #include <mav_msgs/default_topics.h>
00034
00035 #include "Actuators.pb.h"
00036 #include "JointState.pb.h"
00037
00038 #include "rotors_gazebo_plugins/common.h"
00039
00040 namespace gazebo {
00041
00042
00043 static const std::string kDefaultLinkName = "base_link";
00044 static const std::string kDefaultFrameId = "base_link";
00045 static const std::string kDefaultJointStatePubTopic = "joint_states";
00046
00048 class GazeboMultirotorBasePlugin : public ModelPlugin {
00049 typedef std::map<const unsigned int, const physics::JointPtr> MotorNumberToJointMap;
00050 typedef std::pair<const unsigned int, const physics::JointPtr> MotorNumberToJointPair;
00051 public:
00052 GazeboMultirotorBasePlugin()
00053 : ModelPlugin(),
00054 namespace_(kDefaultNamespace),
00055 joint_state_pub_topic_(kDefaultJointStatePubTopic),
00056 actuators_pub_topic_(mav_msgs::default_topics::MOTOR_MEASUREMENT),
00057 link_name_(kDefaultLinkName),
00058 frame_id_(kDefaultFrameId),
00059 rotor_velocity_slowdown_sim_(kDefaultRotorVelocitySlowdownSim),
00060 node_handle_(NULL),
00061 pubs_and_subs_created_(false) {}
00062
00063 virtual ~GazeboMultirotorBasePlugin();
00064
00065 protected:
00066
00070 void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
00071
00074 void OnUpdate(const common::UpdateInfo& );
00075
00076 private:
00077
00080 bool pubs_and_subs_created_;
00081
00086 void CreatePubsAndSubs();
00087
00089 event::ConnectionPtr update_connection_;
00090
00091 physics::WorldPtr world_;
00092 physics::ModelPtr model_;
00093 physics::LinkPtr link_;
00094
00095 physics::Link_V child_links_;
00096
00097 MotorNumberToJointMap motor_joints_;
00098
00099 std::string namespace_;
00100 std::string joint_state_pub_topic_;
00101 std::string actuators_pub_topic_;
00102 std::string link_name_;
00103 std::string frame_id_;
00104 double rotor_velocity_slowdown_sim_;
00105
00106 gazebo::transport::PublisherPtr motor_pub_;
00107
00109 gz_sensor_msgs::Actuators actuators_msg_;
00110
00111 gazebo::transport::PublisherPtr joint_state_pub_;
00112
00114 gz_sensor_msgs::JointState joint_state_msg_;
00115
00116 gazebo::transport::NodePtr node_handle_;
00117 };
00118
00119 }
00120
00121 #endif // ROTORS_GAZEBO_PLUGINS_GAZEBO_MULTIROTOR_BASE_PLUGIN_H
rotors_gazebo_plugins
Author(s): Fadri Furrer, Michael Burri, Mina Kamel, Janosch Nikolic, Markus Achtelik
autogenerated on Thu Apr 18 2019 02:43:43