gazebo_controller_interface.h
Go to the documentation of this file.
1 /*
2  * Copyright 2015 Fadri Furrer, ASL, ETH Zurich, Switzerland
3  * Copyright 2015 Michael Burri, ASL, ETH Zurich, Switzerland
4  * Copyright 2015 Mina Kamel, ASL, ETH Zurich, Switzerland
5  * Copyright 2015 Janosch Nikolic, ASL, ETH Zurich, Switzerland
6  * Copyright 2015 Markus Achtelik, ASL, ETH Zurich, Switzerland
7  * Copyright 2016 Geoffrey Hunter <gbmhunter@gmail.com>
8  *
9  * Licensed under the Apache License, Version 2.0 (the "License");
10  * you may not use this file except in compliance with the License.
11  * You may obtain a copy of the License at
12  *
13  * http://www.apache.org/licenses/LICENSE-2.0
14 
15  * Unless required by applicable law or agreed to in writing, software
16  * distributed under the License is distributed on an "AS IS" BASIS,
17  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
18  * See the License for the specific language governing permissions and
19  * limitations under the License.
20  */
21 
22 
23 #ifndef ROTORS_GAZEBO_PLUGINS_CONTROLLER_INTERFACE_H
24 #define ROTORS_GAZEBO_PLUGINS_CONTROLLER_INTERFACE_H
25 
26 #include <boost/bind.hpp>
27 #include <Eigen/Eigen>
28 #include <stdio.h>
29 
30 #include <gazebo/common/Plugin.hh>
31 #include <gazebo/gazebo.hh>
32 #include <gazebo/physics/physics.hh>
33 
34 #include <mav_msgs/default_topics.h> // This comes from the mav_comm repo
35 
36 #include "Actuators.pb.h"
37 
39 
40 namespace gazebo {
41 
45 static const std::string kDefaultMotorVelocityReferenceTopic = "gazebo/command/motor_speed";
46 
48 
49 class GazeboControllerInterface : public ModelPlugin {
50  public:
52  : ModelPlugin(),
56  // DEFAULT TOPICS
57  motor_velocity_reference_pub_topic_(kDefaultMotorVelocityReferenceTopic),
58  command_motor_speed_sub_topic_(mav_msgs::default_topics::COMMAND_ACTUATORS),
59  //---------------
60  node_handle_(NULL){}
62 
63  void InitializeParams();
64  void Publish();
65 
66  protected:
67  void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
68  void OnUpdate(const common::UpdateInfo& /*_info*/);
69 
70  private:
71 
75 
79 
84  void CreatePubsAndSubs();
85 
88  Eigen::VectorXd input_reference_;
89 
90  //===== VARIABLES READ FROM SDF FILE =====//
91  std::string namespace_;
94 
95 
96  gazebo::transport::NodePtr node_handle_;
97  gazebo::transport::PublisherPtr motor_velocity_reference_pub_;
98  gazebo::transport::SubscriberPtr cmd_motor_sub_;
99 
100  physics::ModelPtr model_;
101  physics::WorldPtr world_;
102 
104  event::ConnectionPtr updateConnection_;
105 
106  boost::thread callback_queue_thread_;
107 
108  void QueueThread();
109 
110  void CommandMotorCallback(GzActuatorsMsgPtr& actuators_msg);
111 
112 };
113 
114 } // namespace gazebo
115 
116 #endif // ROTORS_GAZEBO_PLUGINS_CONTROLLER_INTERFACE_H
void CommandMotorCallback(GzActuatorsMsgPtr &actuators_msg)
gazebo::transport::SubscriberPtr cmd_motor_sub_
const boost::shared_ptr< const gz_sensor_msgs::Actuators > GzActuatorsMsgPtr
static const std::string kDefaultNamespace
Definition: common.h:48
event::ConnectionPtr updateConnection_
Pointer to the update event connection.
static const std::string kDefaultMotorVelocityReferenceTopic
Motor speed topic name.
void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
bool pubs_and_subs_created_
Flag that is set to true once CreatePubsAndSubs() is called, used to prevent CreatePubsAndSubs() from...
gazebo::transport::PublisherPtr motor_velocity_reference_pub_
void CreatePubsAndSubs()
Creates all required publishers and subscribers, incl. routing of messages to/from ROS if required...
void OnUpdate(const common::UpdateInfo &)
bool received_first_reference_
Gets set to true the first time a motor command is received.


rotors_gazebo_plugins
Author(s): Fadri Furrer, Michael Burri, Mina Kamel, Janosch Nikolic, Markus Achtelik
autogenerated on Mon Feb 28 2022 23:39:03