gazebo_controller_interface.h
3.03 KB
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
/*
* 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 <boost/bind.hpp>
#include <Eigen/Eigen>
#include <gazebo/common/common.hh>
#include <gazebo/common/Plugin.hh>
#include <gazebo/gazebo.hh>
#include <gazebo/physics/physics.hh>
#include "CommandMotorSpeed.pb.h"
#include "MotorSpeed.pb.h"
#include "gazebo/transport/transport.hh"
#include "gazebo/msgs/msgs.hh"
#include <ignition/math.hh>
#include <stdio.h>
#include "common.h"
namespace gazebo {
typedef const boost::shared_ptr<const mav_msgs::msgs::CommandMotorSpeed> CommandMotorSpeedPtr;
typedef const boost::shared_ptr<const mav_msgs::msgs::MotorSpeed> MotorSpeedPtr;
// Default values
static const std::string kDefaultNamespace = "";
// This just proxies the motor commands from command/motor_speed to the single motors via internal
// ConsPtr passing, such that the original commands don't have to go n_motors-times over the wire.
static const std::string kDefaultMotorVelocityReferencePubTopic = "/gazebo/command/motor_speed";
static const std::string kDefaultCommandMotorSpeedSubTopic = "/command/motor_speed";
class GazeboControllerInterface : public ModelPlugin {
public:
GazeboControllerInterface()
: ModelPlugin(),
received_first_referenc_(false),
namespace_(kDefaultNamespace),
motor_velocity_reference_pub_topic_(kDefaultMotorVelocityReferencePubTopic),
command_motor_speed_sub_topic_(kDefaultCommandMotorSpeedSubTopic) {}
~GazeboControllerInterface();
void InitializeParams();
void Publish();
protected:
void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
void OnUpdate(const common::UpdateInfo& /*_info*/);
private:
bool received_first_referenc_;
Eigen::VectorXd input_reference_;
std::string namespace_;
std::string motor_velocity_reference_pub_topic_;
std::string command_motor_speed_sub_topic_;
transport::NodePtr node_handle_;
transport::PublisherPtr motor_velocity_reference_pub_;
transport::SubscriberPtr cmd_motor_sub_;
physics::ModelPtr model_;
physics::WorldPtr world_;
/// \brief Pointer to the update event connection.
event::ConnectionPtr updateConnection_;
boost::thread callback_queue_thread_;
void QueueThread();
void CommandMotorCallback(CommandMotorSpeedPtr &input_reference_msg);
};
}