29 #ifndef HECTOR_QUADROTOR_GAZEBO_PLUGINS_QUADROTOR_SIMPLE_CONTROLLER_H 30 #define HECTOR_QUADROTOR_GAZEBO_PLUGINS_QUADROTOR_SIMPLE_CONTROLLER_H 32 #include <gazebo/common/Plugin.hh> 37 #include <geometry_msgs/Twist.h> 38 #include <sensor_msgs/Imu.h> 39 #include <nav_msgs/Odometry.h> 40 #include <std_srvs/Empty.h> 54 virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
84 bool EngageCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
85 bool ShutdownCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
88 #if (GAZEBO_MAJOR_VERSION >= 8) 89 ignition::math::Pose3d
pose;
111 virtual void Load(sdf::ElementPtr _sdf,
const std::string& prefix =
"");
124 double update(
double input,
double x,
double dx,
double dt);
137 #if (GAZEBO_MAJOR_VERSION >= 8) 138 ignition::math::Vector3d
inertia;
144 #if (GAZEBO_MAJOR_VERSION >= 8) 156 #endif // HECTOR_QUADROTOR_GAZEBO_PLUGINS_QUADROTOR_SIMPLE_CONTROLLER_H
physics::LinkPtr link
The link referred to by this plugin.
double update(double input, double x, double dx, double dt)
struct gazebo::GazeboQuadrotorSimpleController::Controllers controllers_
ros::Subscriber imu_subscriber_
std::string velocity_topic_
void ImuCallback(const sensor_msgs::ImuConstPtr &)
virtual ~GazeboQuadrotorSimpleController()
math::Vector3 angular_velocity
virtual void Load(sdf::ElementPtr _sdf, const std::string &prefix="")
ros::ServiceServer shutdown_service_server_
ros::CallbackQueue callback_queue_
void VelocityCallback(const geometry_msgs::TwistConstPtr &)
ros::NodeHandle * node_handle_
bool EngageCallback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
math::Vector3 acceleration
GazeboQuadrotorSimpleController()
std::string wrench_topic_
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
event::ConnectionPtr updateConnection
bool ShutdownCallback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
ros::Subscriber state_subscriber_
void StateCallback(const nav_msgs::OdometryConstPtr &)
physics::WorldPtr world
The parent World.
ros::Publisher wrench_publisher_
ros::ServiceServer engage_service_server_
geometry_msgs::Twist velocity_command_
ros::Subscriber velocity_subscriber_