gazebo_gimbal_controller_plugin.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2012-2016 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 /* Desc: A basic gimbal controller
18  * Author: John Hsu
19  */
20 
21 #ifndef _GAZEBO_GIMBAL_CONTROLLER_PLUGIN_HH_
22 #define _GAZEBO_GIMBAL_CONTROLLER_PLUGIN_HH_
23 
24 #include <string>
25 #include <vector>
26 
27 #include <gazebo/common/PID.hh>
28 #include <gazebo/common/Plugin.hh>
29 #include <gazebo/physics/physics.hh>
30 #include <gazebo/transport/transport.hh>
31 #include <gazebo/util/system.hh>
32 #include <gazebo/sensors/sensors.hh>
33 
34 namespace gazebo
35 {
36  class GAZEBO_VISIBLE GimbalControllerPlugin : public ModelPlugin
37  {
39  public: GimbalControllerPlugin();
40 
41  public: virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
42 
43  public: virtual void Init();
44 
45  private: void OnUpdate();
46 
47  private: void OnPitchStringMsg(ConstAnyPtr &_msg);
48  private: void OnRollStringMsg(ConstAnyPtr &_msg);
49  private: void OnYawStringMsg(ConstAnyPtr &_msg);
50 
57  private: double NormalizeAbout(double _angle, double _reference);
58 
64  private: double ShortestAngularDistance(double _from, double _to);
65 
66  private: sdf::ElementPtr sdf;
67 
68  private: std::vector<event::ConnectionPtr> connections;
69 
70  private: transport::SubscriberPtr pitchSub;
71  private: transport::SubscriberPtr rollSub;
72  private: transport::SubscriberPtr yawSub;
73 
74  private: transport::PublisherPtr pitchPub;
75  private: transport::PublisherPtr rollPub;
76  private: transport::PublisherPtr yawPub;
77 
78  private: physics::ModelPtr model;
79 
81  private: physics::JointPtr yawJoint;
82 
84  private: physics::JointPtr rollJoint;
85 
87  private: physics::JointPtr pitchJoint;
88 
89  private: sensors::ImuSensorPtr imuSensor;
90 
91  private: std::string status;
92 
93  private: double pitchCommand;
94  private: double yawCommand;
95  private: double rollCommand;
96 
97  private: transport::NodePtr node;
98 
99  private: common::PID pitchPid;
100  private: common::PID rollPid;
101  private: common::PID yawPid;
102  private: common::Time lastUpdateTime;
103 
104  private: ignition::ignition::math::Vector3d ThreeAxisRot(
105  double r11, double r12, double r21, double r31, double r32);
106  private: ignition::ignition::math::Vector3d QtoZXY(
107  const ignition::math::Quaterniond &_q);
108  };
109 }
110 #endif
physics::JointPtr pitchJoint
camera pitch joint
physics::JointPtr rollJoint
camera roll joint
std::vector< event::ConnectionPtr > connections


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