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

Public Member Functions

void cmd_velCommandCallback (const geometry_msgs::TwistConstPtr &command)
 
virtual bool init (hector_quadrotor_interface::QuadrotorInterface *interface, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
 
void reset ()
 
virtual void starting (const ros::Time &time)
 
virtual void stopping (const ros::Time &time)
 
void twistCommandCallback (const geometry_msgs::TwistStampedConstPtr &command)
 
virtual void update (const ros::Time &time, const ros::Duration &period)
 
 VelocityController ()
 
virtual ~VelocityController ()
 
- Public Member Functions inherited from controller_interface::Controller< hector_quadrotor_interface::QuadrotorInterface >
 Controller ()
 
virtual bool init (hector_quadrotor_interface::QuadrotorInterface *, 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

AttitudeCommandHandlePtr attitude_output_
 
std::string base_link_frame_
 
std::string base_stabilized_frame_
 
ros::Subscriber cmd_vel_subscriber_
 
boost::mutex command_mutex_
 
double inertia_ [3]
 
double load_factor_limit_
 
double mass_
 
MotorStatusHandlePtr motor_status_
 
struct {
   control_toolbox::Pid   x
 
   control_toolbox::Pid   y
 
   control_toolbox::Pid   z
 
pid_
 
PoseHandlePtr pose_
 
std::string tf_prefix_
 
ThrustCommandHandlePtr thrust_output_
 
TwistHandlePtr twist_
 
geometry_msgs::TwistStamped twist_command_
 
TwistCommandHandlePtr twist_input_
 
hector_quadrotor_interface::TwistLimiter twist_limiter_
 
ros::Subscriber twist_subscriber_
 
std::string world_frame_
 
YawrateCommandHandlePtr yawrate_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< hector_quadrotor_interface::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 52 of file velocity_controller.cpp.

Constructor & Destructor Documentation

hector_quadrotor_controllers::VelocityController::VelocityController ( )
inline

Definition at line 55 of file velocity_controller.cpp.

virtual hector_quadrotor_controllers::VelocityController::~VelocityController ( )
inlinevirtual

Definition at line 59 of file velocity_controller.cpp.

Member Function Documentation

void hector_quadrotor_controllers::VelocityController::cmd_velCommandCallback ( const geometry_msgs::TwistConstPtr &  command)
inline

Definition at line 161 of file velocity_controller.cpp.

virtual bool hector_quadrotor_controllers::VelocityController::init ( hector_quadrotor_interface::QuadrotorInterface interface,
ros::NodeHandle root_nh,
ros::NodeHandle controller_nh 
)
inlinevirtual
void hector_quadrotor_controllers::VelocityController::reset ( )
inline

Definition at line 110 of file velocity_controller.cpp.

virtual void hector_quadrotor_controllers::VelocityController::starting ( const ros::Time time)
inlinevirtual

Reimplemented from controller_interface::ControllerBase.

Definition at line 120 of file velocity_controller.cpp.

virtual void hector_quadrotor_controllers::VelocityController::stopping ( const ros::Time time)
inlinevirtual

Reimplemented from controller_interface::ControllerBase.

Definition at line 125 of file velocity_controller.cpp.

void hector_quadrotor_controllers::VelocityController::twistCommandCallback ( const geometry_msgs::TwistStampedConstPtr &  command)
inline

Definition at line 132 of file velocity_controller.cpp.

virtual void hector_quadrotor_controllers::VelocityController::update ( const ros::Time time,
const ros::Duration period 
)
inlinevirtual

Implements controller_interface::ControllerBase.

Definition at line 184 of file velocity_controller.cpp.

Member Data Documentation

AttitudeCommandHandlePtr hector_quadrotor_controllers::VelocityController::attitude_output_
private

Definition at line 281 of file velocity_controller.cpp.

std::string hector_quadrotor_controllers::VelocityController::base_link_frame_
private

Definition at line 291 of file velocity_controller.cpp.

std::string hector_quadrotor_controllers::VelocityController::base_stabilized_frame_
private

Definition at line 291 of file velocity_controller.cpp.

ros::Subscriber hector_quadrotor_controllers::VelocityController::cmd_vel_subscriber_
private

Definition at line 286 of file velocity_controller.cpp.

boost::mutex hector_quadrotor_controllers::VelocityController::command_mutex_
private

Definition at line 303 of file velocity_controller.cpp.

double hector_quadrotor_controllers::VelocityController::inertia_[3]
private

Definition at line 301 of file velocity_controller.cpp.

double hector_quadrotor_controllers::VelocityController::load_factor_limit_
private

Definition at line 299 of file velocity_controller.cpp.

double hector_quadrotor_controllers::VelocityController::mass_
private

Definition at line 300 of file velocity_controller.cpp.

MotorStatusHandlePtr hector_quadrotor_controllers::VelocityController::motor_status_
private

Definition at line 278 of file velocity_controller.cpp.

struct { ... } hector_quadrotor_controllers::VelocityController::pid_
PoseHandlePtr hector_quadrotor_controllers::VelocityController::pose_
private

Definition at line 276 of file velocity_controller.cpp.

std::string hector_quadrotor_controllers::VelocityController::tf_prefix_
private

Definition at line 292 of file velocity_controller.cpp.

ThrustCommandHandlePtr hector_quadrotor_controllers::VelocityController::thrust_output_
private

Definition at line 283 of file velocity_controller.cpp.

TwistHandlePtr hector_quadrotor_controllers::VelocityController::twist_
private

Definition at line 277 of file velocity_controller.cpp.

geometry_msgs::TwistStamped hector_quadrotor_controllers::VelocityController::twist_command_
private

Definition at line 288 of file velocity_controller.cpp.

TwistCommandHandlePtr hector_quadrotor_controllers::VelocityController::twist_input_
private

Definition at line 280 of file velocity_controller.cpp.

hector_quadrotor_interface::TwistLimiter hector_quadrotor_controllers::VelocityController::twist_limiter_
private

Definition at line 290 of file velocity_controller.cpp.

ros::Subscriber hector_quadrotor_controllers::VelocityController::twist_subscriber_
private

Definition at line 285 of file velocity_controller.cpp.

std::string hector_quadrotor_controllers::VelocityController::world_frame_
private

Definition at line 291 of file velocity_controller.cpp.

control_toolbox::Pid hector_quadrotor_controllers::VelocityController::x

Definition at line 296 of file velocity_controller.cpp.

control_toolbox::Pid hector_quadrotor_controllers::VelocityController::y

Definition at line 296 of file velocity_controller.cpp.

YawrateCommandHandlePtr hector_quadrotor_controllers::VelocityController::yawrate_output_
private

Definition at line 282 of file velocity_controller.cpp.

control_toolbox::Pid hector_quadrotor_controllers::VelocityController::z

Definition at line 296 of file velocity_controller.cpp.


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


hector_quadrotor_controllers
Author(s): Johannes Meyer , Paul Bovbel
autogenerated on Mon Jun 10 2019 13:36:53