Public Member Functions | Private Attributes | List of all members
controller::ProjectorController Class Reference

#include <projector_controller.h>

Inheritance diagram for controller::ProjectorController:
Inheritance graph
[legend]

Public Member Functions

bool init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
 
 ProjectorController ()
 
void starting ()
 
void stopping ()
 
void update ()
 
 ~ProjectorController ()
 
- Public Member Functions inherited from pr2_controller_interface::Controller
 Controller ()
 
bool getController (const std::string &name, int sched, ControllerType *&c)
 
bool initRequest (ControllerProvider *cp, pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
 
bool isRunning ()
 
void starting (const ros::Time &time)
 
bool startRequest ()
 
void stopping (const ros::Time &time)
 
bool stopRequest ()
 
void update (const ros::Time &time, const ros::Duration &period)
 
void updateRequest ()
 
virtual ~Controller ()
 

Private Attributes

std::string actuator_name_
 
double current_setting_
 
boost::scoped_ptr< realtime_tools::RealtimePublisher< std_msgs::Header > > falling_edge_pub_
 
ros::NodeHandle node_handle_
 
uint32_t old_falling_
 
uint32_t old_rising_
 
pr2_hardware_interface::Projectorprojector_
 
boost::scoped_ptr< realtime_tools::RealtimePublisher< std_msgs::Header > > rising_edge_pub_
 
pr2_mechanism_model::RobotStaterobot_
 
double start_time_
 

Additional Inherited Members

- Public Attributes inherited from pr2_controller_interface::Controller
std::vector< std::string > after_list_
 
 AFTER_ME
 
std::vector< std::string > before_list_
 
 BEFORE_ME
 
 CONSTRUCTED
 
 INITIALIZED
 
 RUNNING
 
enum pr2_controller_interface::Controller:: { ... }  state_
 

Detailed Description

Definition at line 47 of file projector_controller.h.

Constructor & Destructor Documentation

ProjectorController::ProjectorController ( )

Definition at line 44 of file projector_controller.cpp.

ProjectorController::~ProjectorController ( )

Definition at line 49 of file projector_controller.cpp.

Member Function Documentation

bool ProjectorController::init ( pr2_mechanism_model::RobotState robot,
ros::NodeHandle n 
)
virtual

Implements pr2_controller_interface::Controller.

Definition at line 106 of file projector_controller.cpp.

void ProjectorController::starting ( )
virtual

Reimplemented from pr2_controller_interface::Controller.

Definition at line 88 of file projector_controller.cpp.

void ProjectorController::stopping ( )
virtual

Reimplemented from pr2_controller_interface::Controller.

Definition at line 98 of file projector_controller.cpp.

void ProjectorController::update ( void  )
virtual
Todo:
These calculations stink but they will do for now...

Implements pr2_controller_interface::Controller.

Definition at line 53 of file projector_controller.cpp.

Member Data Documentation

std::string controller::ProjectorController::actuator_name_
private

Definition at line 74 of file projector_controller.h.

double controller::ProjectorController::current_setting_
private

Definition at line 76 of file projector_controller.h.

boost::scoped_ptr< realtime_tools::RealtimePublisher< std_msgs::Header> > controller::ProjectorController::falling_edge_pub_
private

Definition at line 69 of file projector_controller.h.

ros::NodeHandle controller::ProjectorController::node_handle_
private

Definition at line 71 of file projector_controller.h.

uint32_t controller::ProjectorController::old_falling_
private

Definition at line 65 of file projector_controller.h.

uint32_t controller::ProjectorController::old_rising_
private

Definition at line 64 of file projector_controller.h.

pr2_hardware_interface::Projector* controller::ProjectorController::projector_
private

Definition at line 62 of file projector_controller.h.

boost::scoped_ptr< realtime_tools::RealtimePublisher< std_msgs::Header> > controller::ProjectorController::rising_edge_pub_
private

Definition at line 69 of file projector_controller.h.

pr2_mechanism_model::RobotState* controller::ProjectorController::robot_
private

Definition at line 61 of file projector_controller.h.

double controller::ProjectorController::start_time_
private

Definition at line 78 of file projector_controller.h.


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


ethercat_trigger_controllers
Author(s): Blaise Gassend
autogenerated on Wed Jun 5 2019 19:33:55