Public Member Functions | Private Attributes | List of all members
hector_quadrotor_controller::TwistController Class Reference
Inheritance diagram for hector_quadrotor_controller::TwistController:
Inheritance graph
[legend]

Public Member Functions

void cmd_velCommandCallback (const geometry_msgs::TwistConstPtr &command)
 
bool engageCallback (std_srvs::Empty::Request &, std_srvs::Empty::Response &)
 
bool init (QuadrotorInterface *interface, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
 
void reset ()
 
bool shutdownCallback (std_srvs::Empty::Request &, std_srvs::Empty::Response &)
 
void starting (const ros::Time &time)
 
void stopping (const ros::Time &time)
 
void twistCommandCallback (const geometry_msgs::TwistStampedConstPtr &command)
 
 TwistController ()
 
void update (const ros::Time &time, const ros::Duration &period)
 
 ~TwistController ()
 
- Public Member Functions inherited from controller_interface::Controller< QuadrotorInterface >
 Controller ()
 
virtual bool init (QuadrotorInterface *, ros::NodeHandle &)
 
virtual bool init (QuadrotorInterface *, ros::NodeHandle &, ros::NodeHandle &)
 
virtual ~Controller ()
 
- Public Member Functions inherited from controller_interface::ControllerBase
 ControllerBase ()
 
bool isRunning ()
 
bool isRunning ()
 
bool startRequest (const ros::Time &time)
 
bool startRequest (const ros::Time &time)
 
bool stopRequest (const ros::Time &time)
 
bool stopRequest (const ros::Time &time)
 
void updateRequest (const ros::Time &time, const ros::Duration &period)
 
void updateRequest (const ros::Time &time, const ros::Duration &period)
 
virtual ~ControllerBase ()
 

Private Attributes

AccelerationHandlePtr acceleration_
 
bool auto_engage_
 
std::string base_link_frame_
 
ros::Subscriber cmd_vel_subscriber_
 
geometry_msgs::TwistStamped command_
 
bool command_given_in_stabilized_frame_
 
boost::mutex command_mutex_
 
ros::ServiceServer engage_service_server_
 
double inertia_ [3]
 
geometry_msgs::Wrench limits_
 
double linear_z_control_error_
 
double load_factor_limit
 
double mass_
 
bool motors_running_
 
ros::NodeHandle node_handle_
 
struct {
   struct {
      PID   x
 
      PID   y
 
      PID   z
 
   }   angular
 
   struct {
      PID   x
 
      PID   y
 
      PID   z
 
   }   linear
 
pid_
 
PoseHandlePtr pose_
 
ros::ServiceServer shutdown_service_server_
 
TwistHandlePtr twist_
 
TwistCommandHandlePtr twist_input_
 
ros::Subscriber twist_subscriber_
 
geometry_msgs::WrenchStamped wrench_
 
WrenchCommandHandlePtr wrench_output_
 

Additional Inherited Members

- Public Types inherited from controller_interface::ControllerBase
typedef std::vector< hardware_interface::InterfaceResourcesClaimedResources
 
- Public Attributes inherited from controller_interface::ControllerBase
 CONSTRUCTED
 
 INITIALIZED
 
 RUNNING
 
enum controller_interface::ControllerBase:: { ... }  state_
 
- Protected Member Functions inherited from controller_interface::Controller< QuadrotorInterface >
std::string getHardwareInterfaceType () const
 
virtual bool initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources)
 

Detailed Description

Definition at line 49 of file twist_controller.cpp.

Constructor & Destructor Documentation

hector_quadrotor_controller::TwistController::TwistController ( )
inline

Definition at line 52 of file twist_controller.cpp.

hector_quadrotor_controller::TwistController::~TwistController ( )
inline

Definition at line 55 of file twist_controller.cpp.

Member Function Documentation

void hector_quadrotor_controller::TwistController::cmd_velCommandCallback ( const geometry_msgs::TwistConstPtr &  command)
inline

Definition at line 133 of file twist_controller.cpp.

bool hector_quadrotor_controller::TwistController::engageCallback ( std_srvs::Empty::Request &  ,
std_srvs::Empty::Response &   
)
inline

Definition at line 145 of file twist_controller.cpp.

bool hector_quadrotor_controller::TwistController::init ( QuadrotorInterface interface,
ros::NodeHandle root_nh,
ros::NodeHandle controller_nh 
)
inline

Definition at line 58 of file twist_controller.cpp.

void hector_quadrotor_controller::TwistController::reset ( )
inline

Definition at line 101 of file twist_controller.cpp.

bool hector_quadrotor_controller::TwistController::shutdownCallback ( std_srvs::Empty::Request &  ,
std_srvs::Empty::Response &   
)
inline

Definition at line 154 of file twist_controller.cpp.

void hector_quadrotor_controller::TwistController::starting ( const ros::Time time)
inlinevirtual

Reimplemented from controller_interface::ControllerBase.

Definition at line 163 of file twist_controller.cpp.

void hector_quadrotor_controller::TwistController::stopping ( const ros::Time time)
inlinevirtual

Reimplemented from controller_interface::ControllerBase.

Definition at line 169 of file twist_controller.cpp.

void hector_quadrotor_controller::TwistController::twistCommandCallback ( const geometry_msgs::TwistStampedConstPtr &  command)
inline

Definition at line 121 of file twist_controller.cpp.

void hector_quadrotor_controller::TwistController::update ( const ros::Time time,
const ros::Duration period 
)
inlinevirtual

Implements controller_interface::ControllerBase.

Definition at line 174 of file twist_controller.cpp.

Member Data Documentation

AccelerationHandlePtr hector_quadrotor_controller::TwistController::acceleration_
private

Definition at line 290 of file twist_controller.cpp.

struct { ... } hector_quadrotor_controller::TwistController::angular
bool hector_quadrotor_controller::TwistController::auto_engage_
private

Definition at line 314 of file twist_controller.cpp.

std::string hector_quadrotor_controller::TwistController::base_link_frame_
private

Definition at line 303 of file twist_controller.cpp.

ros::Subscriber hector_quadrotor_controller::TwistController::cmd_vel_subscriber_
private

Definition at line 296 of file twist_controller.cpp.

geometry_msgs::TwistStamped hector_quadrotor_controller::TwistController::command_
private

Definition at line 300 of file twist_controller.cpp.

bool hector_quadrotor_controller::TwistController::command_given_in_stabilized_frame_
private

Definition at line 302 of file twist_controller.cpp.

boost::mutex hector_quadrotor_controller::TwistController::command_mutex_
private

Definition at line 321 of file twist_controller.cpp.

ros::ServiceServer hector_quadrotor_controller::TwistController::engage_service_server_
private

Definition at line 297 of file twist_controller.cpp.

double hector_quadrotor_controller::TwistController::inertia_[3]
private

Definition at line 317 of file twist_controller.cpp.

geometry_msgs::Wrench hector_quadrotor_controller::TwistController::limits_
private

Definition at line 313 of file twist_controller.cpp.

struct { ... } hector_quadrotor_controller::TwistController::linear
double hector_quadrotor_controller::TwistController::linear_z_control_error_
private

Definition at line 320 of file twist_controller.cpp.

double hector_quadrotor_controller::TwistController::load_factor_limit
private

Definition at line 315 of file twist_controller.cpp.

double hector_quadrotor_controller::TwistController::mass_
private

Definition at line 316 of file twist_controller.cpp.

bool hector_quadrotor_controller::TwistController::motors_running_
private

Definition at line 319 of file twist_controller.cpp.

ros::NodeHandle hector_quadrotor_controller::TwistController::node_handle_
private

Definition at line 294 of file twist_controller.cpp.

struct { ... } hector_quadrotor_controller::TwistController::pid_
PoseHandlePtr hector_quadrotor_controller::TwistController::pose_
private

Definition at line 288 of file twist_controller.cpp.

ros::ServiceServer hector_quadrotor_controller::TwistController::shutdown_service_server_
private

Definition at line 298 of file twist_controller.cpp.

TwistHandlePtr hector_quadrotor_controller::TwistController::twist_
private

Definition at line 289 of file twist_controller.cpp.

TwistCommandHandlePtr hector_quadrotor_controller::TwistController::twist_input_
private

Definition at line 291 of file twist_controller.cpp.

ros::Subscriber hector_quadrotor_controller::TwistController::twist_subscriber_
private

Definition at line 295 of file twist_controller.cpp.

geometry_msgs::WrenchStamped hector_quadrotor_controller::TwistController::wrench_
private

Definition at line 301 of file twist_controller.cpp.

WrenchCommandHandlePtr hector_quadrotor_controller::TwistController::wrench_output_
private

Definition at line 292 of file twist_controller.cpp.

PID hector_quadrotor_controller::TwistController::x

Definition at line 307 of file twist_controller.cpp.

PID hector_quadrotor_controller::TwistController::y

Definition at line 308 of file twist_controller.cpp.

PID hector_quadrotor_controller::TwistController::z

Definition at line 309 of file twist_controller.cpp.


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


hector_quadrotor_controller
Author(s): Johannes Meyer
autogenerated on Sun Jul 10 2016 04:30:49