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 #ifndef _GAZEBO_GIMBAL_CONTROLLER_PLUGIN_HH_
00022 #define _GAZEBO_GIMBAL_CONTROLLER_PLUGIN_HH_
00023
00024 #include <string>
00025 #include <vector>
00026
00027 #include <gazebo/common/PID.hh>
00028 #include <gazebo/common/Plugin.hh>
00029 #include <gazebo/physics/physics.hh>
00030 #include <gazebo/transport/transport.hh>
00031 #include <gazebo/util/system.hh>
00032 #include <gazebo/sensors/sensors.hh>
00033
00034 namespace gazebo
00035 {
00036 class GAZEBO_VISIBLE GimbalControllerPlugin : public ModelPlugin
00037 {
00039 public: GimbalControllerPlugin();
00040
00041 public: virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
00042
00043 public: virtual void Init();
00044
00045 private: void OnUpdate();
00046
00047 private: void OnPitchStringMsg(ConstAnyPtr &_msg);
00048 private: void OnRollStringMsg(ConstAnyPtr &_msg);
00049 private: void OnYawStringMsg(ConstAnyPtr &_msg);
00050
00057 private: double NormalizeAbout(double _angle, double _reference);
00058
00064 private: double ShortestAngularDistance(double _from, double _to);
00065
00066 private: sdf::ElementPtr sdf;
00067
00068 private: std::vector<event::ConnectionPtr> connections;
00069
00070 private: transport::SubscriberPtr pitchSub;
00071 private: transport::SubscriberPtr rollSub;
00072 private: transport::SubscriberPtr yawSub;
00073
00074 private: transport::PublisherPtr pitchPub;
00075 private: transport::PublisherPtr rollPub;
00076 private: transport::PublisherPtr yawPub;
00077
00078 private: physics::ModelPtr model;
00079
00081 private: physics::JointPtr yawJoint;
00082
00084 private: physics::JointPtr rollJoint;
00085
00087 private: physics::JointPtr pitchJoint;
00088
00089 private: sensors::ImuSensorPtr imuSensor;
00090
00091 private: std::string status;
00092
00093 private: double pitchCommand;
00094 private: double yawCommand;
00095 private: double rollCommand;
00096
00097 private: transport::NodePtr node;
00098
00099 private: common::PID pitchPid;
00100 private: common::PID rollPid;
00101 private: common::PID yawPid;
00102 private: common::Time lastUpdateTime;
00103
00104 private: ignition::ignition::math::Vector3d ThreeAxisRot(
00105 double r11, double r12, double r21, double r31, double r32);
00106 private: ignition::ignition::math::Vector3d QtoZXY(
00107 const ignition::math::Quaterniond &_q);
00108 };
00109 }
00110 #endif
rotors_gazebo_plugins
Author(s): Fadri Furrer, Michael Burri, Mina Kamel, Janosch Nikolic, Markus Achtelik
autogenerated on Thu Apr 18 2019 02:43:43