#include <gazebo_quadrotor_simple_controller.h>
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. | |
std::string | link_name_ |
double | mass |
double | max_force_ |
std::string | namespace_ |
ros::NodeHandle * | node_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. | |
ros::Publisher | wrench_publisher_ |
std::string | wrench_topic_ |
Definition at line 47 of file gazebo_quadrotor_simple_controller.h.
Definition at line 39 of file gazebo_quadrotor_simple_controller.cpp.
Definition at line 45 of file gazebo_quadrotor_simple_controller.cpp.
bool gazebo::GazeboQuadrotorSimpleController::EngageCallback | ( | std_srvs::Empty::Request & | , |
std_srvs::Empty::Response & | |||
) | [private] |
Definition at line 228 of file gazebo_quadrotor_simple_controller.cpp.
void gazebo::GazeboQuadrotorSimpleController::ImuCallback | ( | const sensor_msgs::ImuConstPtr & | imu | ) | [private] |
Definition at line 198 of file gazebo_quadrotor_simple_controller.cpp.
void gazebo::GazeboQuadrotorSimpleController::Load | ( | physics::ModelPtr | _model, |
sdf::ElementPtr | _sdf | ||
) | [protected, virtual] |
Definition at line 55 of file gazebo_quadrotor_simple_controller.cpp.
void gazebo::GazeboQuadrotorSimpleController::Reset | ( | ) | [protected, virtual] |
Definition at line 345 of file gazebo_quadrotor_simple_controller.cpp.
bool gazebo::GazeboQuadrotorSimpleController::ShutdownCallback | ( | std_srvs::Empty::Request & | , |
std_srvs::Empty::Response & | |||
) | [private] |
Definition at line 235 of file gazebo_quadrotor_simple_controller.cpp.
void gazebo::GazeboQuadrotorSimpleController::StateCallback | ( | const nav_msgs::OdometryConstPtr & | state | ) | [private] |
Definition at line 205 of file gazebo_quadrotor_simple_controller.cpp.
void gazebo::GazeboQuadrotorSimpleController::Update | ( | ) | [protected, virtual] |
Definition at line 244 of file gazebo_quadrotor_simple_controller.cpp.
void gazebo::GazeboQuadrotorSimpleController::VelocityCallback | ( | const geometry_msgs::TwistConstPtr & | velocity | ) | [private] |
Definition at line 193 of file gazebo_quadrotor_simple_controller.cpp.
math::Vector3 gazebo::GazeboQuadrotorSimpleController::acceleration [private] |
Definition at line 89 of file gazebo_quadrotor_simple_controller.h.
math::Vector3 gazebo::GazeboQuadrotorSimpleController::angular_velocity [private] |
Definition at line 89 of file gazebo_quadrotor_simple_controller.h.
bool gazebo::GazeboQuadrotorSimpleController::auto_engage_ [private] |
Definition at line 100 of file gazebo_quadrotor_simple_controller.h.
Definition at line 66 of file gazebo_quadrotor_simple_controller.h.
struct gazebo::GazeboQuadrotorSimpleController::Controllers gazebo::GazeboQuadrotorSimpleController::controllers_ [private] |
Definition at line 137 of file gazebo_quadrotor_simple_controller.h.
Definition at line 72 of file gazebo_quadrotor_simple_controller.h.
math::Vector3 gazebo::GazeboQuadrotorSimpleController::euler [private] |
Definition at line 89 of file gazebo_quadrotor_simple_controller.h.
math::Vector3 gazebo::GazeboQuadrotorSimpleController::force [private] |
Definition at line 135 of file gazebo_quadrotor_simple_controller.h.
Definition at line 68 of file gazebo_quadrotor_simple_controller.h.
std::string gazebo::GazeboQuadrotorSimpleController::imu_topic_ [private] |
Definition at line 94 of file gazebo_quadrotor_simple_controller.h.
math::Vector3 gazebo::GazeboQuadrotorSimpleController::inertia [private] |
Definition at line 132 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 91 of file gazebo_quadrotor_simple_controller.h.
double gazebo::GazeboQuadrotorSimpleController::mass [private] |
Definition at line 133 of file gazebo_quadrotor_simple_controller.h.
double gazebo::GazeboQuadrotorSimpleController::max_force_ [private] |
Definition at line 97 of file gazebo_quadrotor_simple_controller.h.
std::string gazebo::GazeboQuadrotorSimpleController::namespace_ [private] |
Definition at line 92 of file gazebo_quadrotor_simple_controller.h.
Definition at line 65 of file gazebo_quadrotor_simple_controller.h.
Definition at line 88 of file gazebo_quadrotor_simple_controller.h.
bool gazebo::GazeboQuadrotorSimpleController::running_ [private] |
Definition at line 99 of file gazebo_quadrotor_simple_controller.h.
Definition at line 73 of file gazebo_quadrotor_simple_controller.h.
Definition at line 87 of file gazebo_quadrotor_simple_controller.h.
Definition at line 69 of file gazebo_quadrotor_simple_controller.h.
std::string gazebo::GazeboQuadrotorSimpleController::state_topic_ [private] |
Definition at line 95 of file gazebo_quadrotor_simple_controller.h.
math::Vector3 gazebo::GazeboQuadrotorSimpleController::torque [private] |
Definition at line 135 of file gazebo_quadrotor_simple_controller.h.
Definition at line 138 of file gazebo_quadrotor_simple_controller.h.
math::Vector3 gazebo::GazeboQuadrotorSimpleController::velocity [private] |
Definition at line 89 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.
Definition at line 67 of file gazebo_quadrotor_simple_controller.h.
std::string gazebo::GazeboQuadrotorSimpleController::velocity_topic_ [private] |
Definition at line 93 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.
Definition at line 70 of file gazebo_quadrotor_simple_controller.h.
std::string gazebo::GazeboQuadrotorSimpleController::wrench_topic_ [private] |
Definition at line 96 of file gazebo_quadrotor_simple_controller.h.