Classes | Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | List of all members
gazebo::GazeboQuadrotorSimpleController Class Reference

#include <gazebo_quadrotor_simple_controller.h>

Inheritance diagram for gazebo::GazeboQuadrotorSimpleController:
Inheritance graph
[legend]

Classes

struct  Controllers
 
class  PIDController
 

Public Member Functions

 GazeboQuadrotorSimpleController ()
 
virtual ~GazeboQuadrotorSimpleController ()
 

Protected Member Functions

virtual void Load (physics::ModelPtr _model, sdf::ElementPtr _sdf)
 
virtual void Reset ()
 
virtual void Update ()
 

Private Member Functions

bool EngageCallback (std_srvs::Empty::Request &, std_srvs::Empty::Response &)
 
void ImuCallback (const sensor_msgs::ImuConstPtr &)
 
bool ShutdownCallback (std_srvs::Empty::Request &, std_srvs::Empty::Response &)
 
void StateCallback (const nav_msgs::OdometryConstPtr &)
 
void VelocityCallback (const geometry_msgs::TwistConstPtr &)
 

Private Attributes

math::Vector3 acceleration
 
math::Vector3 angular_velocity
 
bool auto_engage_
 
ros::CallbackQueue callback_queue_
 
struct gazebo::GazeboQuadrotorSimpleController::Controllers controllers_
 
UpdateTimer controlTimer
 
ros::ServiceServer engage_service_server_
 
math::Vector3 euler
 
math::Vector3 force
 
ros::Subscriber imu_subscriber_
 
std::string imu_topic_
 
math::Vector3 inertia
 
physics::LinkPtr link
 The link referred to by this plugin. More...
 
std::string link_name_
 
double mass
 
double max_force_
 
std::string namespace_
 
ros::NodeHandlenode_handle_
 
math::Pose pose
 
bool running_
 
ros::ServiceServer shutdown_service_server_
 
ros::Time state_stamp
 
ros::Subscriber state_subscriber_
 
std::string state_topic_
 
math::Vector3 torque
 
event::ConnectionPtr updateConnection
 
math::Vector3 velocity
 
geometry_msgs::Twist velocity_command_
 
ros::Subscriber velocity_subscriber_
 
std::string velocity_topic_
 
physics::WorldPtr world
 The parent World. More...
 
ros::Publisher wrench_publisher_
 
std::string wrench_topic_
 

Detailed Description

Definition at line 47 of file gazebo_quadrotor_simple_controller.h.

Constructor & Destructor Documentation

gazebo::GazeboQuadrotorSimpleController::GazeboQuadrotorSimpleController ( )

Definition at line 39 of file gazebo_quadrotor_simple_controller.cpp.

gazebo::GazeboQuadrotorSimpleController::~GazeboQuadrotorSimpleController ( )
virtual

Definition at line 45 of file gazebo_quadrotor_simple_controller.cpp.

Member Function Documentation

bool gazebo::GazeboQuadrotorSimpleController::EngageCallback ( std_srvs::Empty::Request &  ,
std_srvs::Empty::Response &   
)
private

Definition at line 252 of file gazebo_quadrotor_simple_controller.cpp.

void gazebo::GazeboQuadrotorSimpleController::ImuCallback ( const sensor_msgs::ImuConstPtr &  imu)
private

Definition at line 206 of file gazebo_quadrotor_simple_controller.cpp.

void gazebo::GazeboQuadrotorSimpleController::Load ( physics::ModelPtr  _model,
sdf::ElementPtr  _sdf 
)
protectedvirtual

Definition at line 58 of file gazebo_quadrotor_simple_controller.cpp.

void gazebo::GazeboQuadrotorSimpleController::Reset ( )
protectedvirtual

Definition at line 423 of file gazebo_quadrotor_simple_controller.cpp.

bool gazebo::GazeboQuadrotorSimpleController::ShutdownCallback ( std_srvs::Empty::Request &  ,
std_srvs::Empty::Response &   
)
private

Definition at line 259 of file gazebo_quadrotor_simple_controller.cpp.

void gazebo::GazeboQuadrotorSimpleController::StateCallback ( const nav_msgs::OdometryConstPtr &  state)
private

Definition at line 219 of file gazebo_quadrotor_simple_controller.cpp.

void gazebo::GazeboQuadrotorSimpleController::Update ( )
protectedvirtual

Definition at line 268 of file gazebo_quadrotor_simple_controller.cpp.

void gazebo::GazeboQuadrotorSimpleController::VelocityCallback ( const geometry_msgs::TwistConstPtr &  velocity)
private

Definition at line 201 of file gazebo_quadrotor_simple_controller.cpp.

Member Data Documentation

math::Vector3 gazebo::GazeboQuadrotorSimpleController::acceleration
private

Definition at line 93 of file gazebo_quadrotor_simple_controller.h.

math::Vector3 gazebo::GazeboQuadrotorSimpleController::angular_velocity
private

Definition at line 93 of file gazebo_quadrotor_simple_controller.h.

bool gazebo::GazeboQuadrotorSimpleController::auto_engage_
private

Definition at line 105 of file gazebo_quadrotor_simple_controller.h.

ros::CallbackQueue gazebo::GazeboQuadrotorSimpleController::callback_queue_
private

Definition at line 66 of file gazebo_quadrotor_simple_controller.h.

struct gazebo::GazeboQuadrotorSimpleController::Controllers gazebo::GazeboQuadrotorSimpleController::controllers_
private
UpdateTimer gazebo::GazeboQuadrotorSimpleController::controlTimer
private

Definition at line 150 of file gazebo_quadrotor_simple_controller.h.

ros::ServiceServer gazebo::GazeboQuadrotorSimpleController::engage_service_server_
private

Definition at line 72 of file gazebo_quadrotor_simple_controller.h.

math::Vector3 gazebo::GazeboQuadrotorSimpleController::euler
private

Definition at line 93 of file gazebo_quadrotor_simple_controller.h.

math::Vector3 gazebo::GazeboQuadrotorSimpleController::force
private

Definition at line 147 of file gazebo_quadrotor_simple_controller.h.

ros::Subscriber gazebo::GazeboQuadrotorSimpleController::imu_subscriber_
private

Definition at line 68 of file gazebo_quadrotor_simple_controller.h.

std::string gazebo::GazeboQuadrotorSimpleController::imu_topic_
private

Definition at line 99 of file gazebo_quadrotor_simple_controller.h.

math::Vector3 gazebo::GazeboQuadrotorSimpleController::inertia
private

Definition at line 140 of file gazebo_quadrotor_simple_controller.h.

physics::LinkPtr gazebo::GazeboQuadrotorSimpleController::link
private

The link referred to by this plugin.

Definition at line 63 of file gazebo_quadrotor_simple_controller.h.

std::string gazebo::GazeboQuadrotorSimpleController::link_name_
private

Definition at line 96 of file gazebo_quadrotor_simple_controller.h.

double gazebo::GazeboQuadrotorSimpleController::mass
private

Definition at line 142 of file gazebo_quadrotor_simple_controller.h.

double gazebo::GazeboQuadrotorSimpleController::max_force_
private

Definition at line 102 of file gazebo_quadrotor_simple_controller.h.

std::string gazebo::GazeboQuadrotorSimpleController::namespace_
private

Definition at line 97 of file gazebo_quadrotor_simple_controller.h.

ros::NodeHandle* gazebo::GazeboQuadrotorSimpleController::node_handle_
private

Definition at line 65 of file gazebo_quadrotor_simple_controller.h.

math::Pose gazebo::GazeboQuadrotorSimpleController::pose
private

Definition at line 92 of file gazebo_quadrotor_simple_controller.h.

bool gazebo::GazeboQuadrotorSimpleController::running_
private

Definition at line 104 of file gazebo_quadrotor_simple_controller.h.

ros::ServiceServer gazebo::GazeboQuadrotorSimpleController::shutdown_service_server_
private

Definition at line 73 of file gazebo_quadrotor_simple_controller.h.

ros::Time gazebo::GazeboQuadrotorSimpleController::state_stamp
private

Definition at line 87 of file gazebo_quadrotor_simple_controller.h.

ros::Subscriber gazebo::GazeboQuadrotorSimpleController::state_subscriber_
private

Definition at line 69 of file gazebo_quadrotor_simple_controller.h.

std::string gazebo::GazeboQuadrotorSimpleController::state_topic_
private

Definition at line 100 of file gazebo_quadrotor_simple_controller.h.

math::Vector3 gazebo::GazeboQuadrotorSimpleController::torque
private

Definition at line 147 of file gazebo_quadrotor_simple_controller.h.

event::ConnectionPtr gazebo::GazeboQuadrotorSimpleController::updateConnection
private

Definition at line 151 of file gazebo_quadrotor_simple_controller.h.

math::Vector3 gazebo::GazeboQuadrotorSimpleController::velocity
private

Definition at line 93 of file gazebo_quadrotor_simple_controller.h.

geometry_msgs::Twist gazebo::GazeboQuadrotorSimpleController::velocity_command_
private

Definition at line 79 of file gazebo_quadrotor_simple_controller.h.

ros::Subscriber gazebo::GazeboQuadrotorSimpleController::velocity_subscriber_
private

Definition at line 67 of file gazebo_quadrotor_simple_controller.h.

std::string gazebo::GazeboQuadrotorSimpleController::velocity_topic_
private

Definition at line 98 of file gazebo_quadrotor_simple_controller.h.

physics::WorldPtr gazebo::GazeboQuadrotorSimpleController::world
private

The parent World.

Definition at line 60 of file gazebo_quadrotor_simple_controller.h.

ros::Publisher gazebo::GazeboQuadrotorSimpleController::wrench_publisher_
private

Definition at line 70 of file gazebo_quadrotor_simple_controller.h.

std::string gazebo::GazeboQuadrotorSimpleController::wrench_topic_
private

Definition at line 101 of file gazebo_quadrotor_simple_controller.h.


The documentation for this class was generated from the following files:


hector_quadrotor_gazebo_plugins
Author(s): Johannes Meyer
autogenerated on Mon Jun 10 2019 13:36:58