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

Public Member Functions

bool init (QuadrotorInterface *interface, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
 
void poseCommandCallback (const geometry_msgs::PoseStampedConstPtr &command)
 
 PoseController ()
 
void reset ()
 
void starting (const ros::Time &time)
 
void stopping (const ros::Time &time)
 
void twistCommandCallback (const geometry_msgs::TwistStampedConstPtr &command)
 
void update (const ros::Time &time, const ros::Duration &period)
 
 ~PoseController ()
 
- 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

ros::NodeHandle node_handle_
 
struct {
   PID   x
 
   PID   y
 
   PID   yaw
 
   PID   z
 
pid_
 
PoseHandlePtr pose_
 
geometry_msgs::PoseStamped pose_command_
 
PoseCommandHandlePtr pose_input_
 
ros::Subscriber pose_subscriber_
 
TwistHandlePtr twist_
 
geometry_msgs::TwistStamped twist_command_
 
TwistCommandHandlePtr twist_input_
 
TwistCommandHandlePtr twist_limit_
 
TwistCommandHandlePtr twist_output_
 
ros::Subscriber twist_subscriber_
 

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 44 of file pose_controller.cpp.

Constructor & Destructor Documentation

hector_quadrotor_controller::PoseController::PoseController ( )
inline

Definition at line 47 of file pose_controller.cpp.

hector_quadrotor_controller::PoseController::~PoseController ( )
inline

Definition at line 49 of file pose_controller.cpp.

Member Function Documentation

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

Definition at line 51 of file pose_controller.cpp.

void hector_quadrotor_controller::PoseController::poseCommandCallback ( const geometry_msgs::PoseStampedConstPtr &  command)
inline

Definition at line 85 of file pose_controller.cpp.

void hector_quadrotor_controller::PoseController::reset ( )
inline

Definition at line 77 of file pose_controller.cpp.

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

Reimplemented from controller_interface::ControllerBase.

Definition at line 107 of file pose_controller.cpp.

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

Reimplemented from controller_interface::ControllerBase.

Definition at line 113 of file pose_controller.cpp.

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

Definition at line 96 of file pose_controller.cpp.

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

Implements controller_interface::ControllerBase.

Definition at line 118 of file pose_controller.cpp.

Member Data Documentation

ros::NodeHandle hector_quadrotor_controller::PoseController::node_handle_
private

Definition at line 189 of file pose_controller.cpp.

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

Definition at line 179 of file pose_controller.cpp.

geometry_msgs::PoseStamped hector_quadrotor_controller::PoseController::pose_command_
private

Definition at line 186 of file pose_controller.cpp.

PoseCommandHandlePtr hector_quadrotor_controller::PoseController::pose_input_
private

Definition at line 180 of file pose_controller.cpp.

ros::Subscriber hector_quadrotor_controller::PoseController::pose_subscriber_
private

Definition at line 190 of file pose_controller.cpp.

TwistHandlePtr hector_quadrotor_controller::PoseController::twist_
private

Definition at line 181 of file pose_controller.cpp.

geometry_msgs::TwistStamped hector_quadrotor_controller::PoseController::twist_command_
private

Definition at line 187 of file pose_controller.cpp.

TwistCommandHandlePtr hector_quadrotor_controller::PoseController::twist_input_
private

Definition at line 182 of file pose_controller.cpp.

TwistCommandHandlePtr hector_quadrotor_controller::PoseController::twist_limit_
private

Definition at line 183 of file pose_controller.cpp.

TwistCommandHandlePtr hector_quadrotor_controller::PoseController::twist_output_
private

Definition at line 184 of file pose_controller.cpp.

ros::Subscriber hector_quadrotor_controller::PoseController::twist_subscriber_
private

Definition at line 191 of file pose_controller.cpp.

PID hector_quadrotor_controller::PoseController::x

Definition at line 194 of file pose_controller.cpp.

PID hector_quadrotor_controller::PoseController::y

Definition at line 195 of file pose_controller.cpp.

PID hector_quadrotor_controller::PoseController::yaw

Definition at line 197 of file pose_controller.cpp.

PID hector_quadrotor_controller::PoseController::z

Definition at line 196 of file pose_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