forked from PX4/PX4-SITL_gazebo-classic
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathgazebo_multirotor_base_plugin.h
95 lines (74 loc) · 3.05 KB
/
gazebo_multirotor_base_plugin.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
/*
* Copyright 2015 Fadri Furrer, ASL, ETH Zurich, Switzerland
* Copyright 2015 Michael Burri, ASL, ETH Zurich, Switzerland
* Copyright 2015 Mina Kamel, ASL, ETH Zurich, Switzerland
* Copyright 2015 Janosch Nikolic, ASL, ETH Zurich, Switzerland
* Copyright 2015 Markus Achtelik, ASL, ETH Zurich, Switzerland
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#include <string>
#include <gazebo/common/common.hh>
#include <gazebo/common/Plugin.hh>
#include <gazebo/gazebo.hh>
#include <gazebo/physics/physics.hh>
#include "common.h"
#include "gazebo/math/Vector3.hh"
#include "gazebo/transport/transport.hh"
#include "gazebo/msgs/msgs.hh"
#include "MotorSpeed.pb.h"
namespace gazebo {
typedef const boost::shared_ptr<const mav_msgs::msgs::MotorSpeed> MotorSpeedPtr;
// Default values
static const std::string kDefaultNamespace = "";
static const std::string kDefaultMotorPubTopic = "/motors";
static const std::string kDefaultLinkName = "base_link";
static const std::string kDefaultFrameId = "base_link";
static constexpr double kDefaultRotorVelocitySlowdownSim = 10.0;
/// \brief This plugin publishes the motor speeds of your multirotor model.
class GazeboMultirotorBasePlugin : public ModelPlugin {
typedef std::map<const unsigned int, const physics::JointPtr> MotorNumberToJointMap;
typedef std::pair<const unsigned int, const physics::JointPtr> MotorNumberToJointPair;
public:
GazeboMultirotorBasePlugin()
: ModelPlugin(),
namespace_(kDefaultNamespace),
motor_pub_topic_(kDefaultMotorPubTopic),
link_name_(kDefaultLinkName),
frame_id_(kDefaultFrameId),
rotor_velocity_slowdown_sim_(kDefaultRotorVelocitySlowdownSim) {}
virtual ~GazeboMultirotorBasePlugin();
protected:
/// \brief Load the plugin.
/// \param[in] _model Pointer to the model that loaded this plugin.
/// \param[in] _sdf SDF element that describes the plugin.
void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
/// \brief Called when the world is updated.
/// \param[in] _info Update timing information.
void OnUpdate(const common::UpdateInfo& /*_info*/);
private:
/// \brief Pointer to the update event connection.
event::ConnectionPtr update_connection_;
physics::WorldPtr world_;
physics::ModelPtr model_;
physics::LinkPtr link_;
physics::Link_V child_links_;
MotorNumberToJointMap motor_joints_;
std::string namespace_;
std::string motor_pub_topic_;
std::string link_name_;
std::string frame_id_;
double rotor_velocity_slowdown_sim_;
transport::NodePtr node_handle_;
transport::PublisherPtr motor_pub_;
};
}