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

#include <trigger_controller.h>

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

Public Member Functions

bool init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
 
 TriggerController ()
 
void update ()
 
 ~TriggerController ()
 
- 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)
 
virtual void starting ()
 
bool startRequest ()
 
void stopping (const ros::Time &time)
 
virtual void stopping ()
 
bool stopRequest ()
 
void update (const ros::Time &time, const ros::Duration &period)
 
void updateRequest ()
 
virtual ~Controller ()
 

Static Public Member Functions

static double getTick (double t, trigger_configuration const &config)
 Convert time to an unrolled phase (in cycles). More...
 
static double getTick (const ros::Time &t, trigger_configuration const &config)
 Convert time to an unrolled phase (in cycles). More...
 
static ros::Duration getTickDuration (trigger_configuration &config)
 Gets the time during which the output will be active during each cycle. More...
 
static double getTickDurationSec (trigger_configuration &config)
 Gets the time during which the output will be active during each cycle. More...
 
static ros::Time getTickStartTime (ros::Time time, trigger_configuration const &config)
 Gets the ros::Time at which a cycle starts. More...
 
static ros::Time getTickStartTimeFromPhase (double tick, trigger_configuration const &config)
 Gets the ros::Time at which a cycle starts. More...
 
static double getTickStartTimeSec (double time, trigger_configuration const &config)
 Gets the ros::Time at which a cycle starts. More...
 
static double getTickStartTimeSecFromPhase (double tick, trigger_configuration const &config)
 Gets the ros::Time at which a cycle starts. More...
 

Private Member Functions

double getTick ()
 
bool setWaveformSrv (trigger_configuration &req, ethercat_trigger_controllers::SetWaveform::Response &resp)
 

Private Attributes

std::string actuator_name_
 
trigger_configuration config_
 
pr2_hardware_interface::DigitalOutCommanddigital_out_command_
 
boost::scoped_ptr< realtime_tools::RealtimePublisher< std_msgs::Header > > falling_edge_pub_
 
bool last_out_
 
ros::NodeHandle node_handle_
 
double prev_tick_
 
boost::scoped_ptr< realtime_tools::RealtimePublisher< std_msgs::Header > > rising_edge_pub_
 
pr2_mechanism_model::RobotStaterobot_
 
ros::ServiceServer set_waveform_handle_
 

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 58 of file trigger_controller.h.

Constructor & Destructor Documentation

TriggerController::TriggerController ( )

Definition at line 69 of file trigger_controller.cpp.

TriggerController::~TriggerController ( )

Definition at line 74 of file trigger_controller.cpp.

Member Function Documentation

static double controller::TriggerController::getTick ( double  t,
trigger_configuration const &  config 
)
inlinestatic

Convert time to an unrolled phase (in cycles).

At time 0, the unrolled phase is equal to -config.phase. Thereafter, phase increases at a rate of 1/config.rep_rate.

Parameters
tTime for which the phase should be evaluated.
configTrigger configuration for which the phase should be evaluated.
Returns
Unrolled phase in cycles.

Definition at line 82 of file trigger_controller.h.

static double controller::TriggerController::getTick ( const ros::Time t,
trigger_configuration const &  config 
)
inlinestatic

Convert time to an unrolled phase (in cycles).

At time 0, the unrolled phase is equal to -config.phase. Thereafter, phase increases at a rate of 1/config.rep_rate. This function returns the unrolled phase.

Parameters
tTime for which the phase should be evaluated.
configTrigger configuration for which the phase should be evaluated.
Returns
Unrolled phase in cycles.

Definition at line 101 of file trigger_controller.h.

double TriggerController::getTick ( )
private

Definition at line 78 of file trigger_controller.cpp.

static ros::Duration controller::TriggerController::getTickDuration ( trigger_configuration config)
inlinestatic

Gets the time during which the output will be active during each cycle.

This function determines how much time the output is active for during each cycle.

Parameters
configTrigger configuration for which the cycle start should be evaluated.
Returns
Cycle start time.

Definition at line 194 of file trigger_controller.h.

static double controller::TriggerController::getTickDurationSec ( trigger_configuration config)
inlinestatic

Gets the time during which the output will be active during each cycle.

This function determines how much time the output is active for during each cycle.

Parameters
configTrigger configuration for which the cycle start should be evaluated.
Returns
Cycle start time.

Definition at line 211 of file trigger_controller.h.

static ros::Time controller::TriggerController::getTickStartTime ( ros::Time  time,
trigger_configuration const &  config 
)
inlinestatic

Gets the ros::Time at which a cycle starts.

This function takes a time, and returns the time at which the current cycle started. That is, the most recent time at which the phase was integer.

Parameters
tickTime for which to perform the computation.
configTrigger configuration for which the cycle start should be evaluated.
Returns
Cycle start time.

Definition at line 158 of file trigger_controller.h.

static ros::Time controller::TriggerController::getTickStartTimeFromPhase ( double  tick,
trigger_configuration const &  config 
)
inlinestatic

Gets the ros::Time at which a cycle starts.

This function takes an unrolled phase, and returns the time at which the current cycle started. That is, the most recent time at which the phase was integer.

Parameters
tickUnrolled phase.
configTrigger configuration for which the cycle start should be evaluated.
Returns
Cycle start time.

Definition at line 139 of file trigger_controller.h.

static double controller::TriggerController::getTickStartTimeSec ( double  time,
trigger_configuration const &  config 
)
inlinestatic

Gets the ros::Time at which a cycle starts.

This function takes a time, and returns the time at which the current cycle started. That is, the most recent time at which the phase was integer.

Parameters
tickTime for which to perform the computation.
configTrigger configuration for which the cycle start should be evaluated.
Returns
Cycle start time.

Definition at line 177 of file trigger_controller.h.

static double controller::TriggerController::getTickStartTimeSecFromPhase ( double  tick,
trigger_configuration const &  config 
)
inlinestatic

Gets the ros::Time at which a cycle starts.

This function takes an unrolled phase, and returns the time at which the current cycle started. That is, the most recent time at which the phase was integer.

Parameters
tickUnrolled phase.
configTrigger configuration for which the cycle start should be evaluated.
Returns
Cycle start time.

Definition at line 120 of file trigger_controller.h.

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

Implements pr2_controller_interface::Controller.

Definition at line 149 of file trigger_controller.cpp.

bool TriggerController::setWaveformSrv ( trigger_configuration req,
ethercat_trigger_controllers::SetWaveform::Response &  resp 
)
private

Definition at line 211 of file trigger_controller.cpp.

void TriggerController::update ( void  )
virtual

Implements pr2_controller_interface::Controller.

Definition at line 83 of file trigger_controller.cpp.

Member Data Documentation

std::string controller::TriggerController::actuator_name_
private

Definition at line 242 of file trigger_controller.h.

trigger_configuration controller::TriggerController::config_
private

Definition at line 241 of file trigger_controller.h.

pr2_hardware_interface::DigitalOutCommand* controller::TriggerController::digital_out_command_
private

Definition at line 228 of file trigger_controller.h.

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

Definition at line 237 of file trigger_controller.h.

bool controller::TriggerController::last_out_
private

Definition at line 238 of file trigger_controller.h.

ros::NodeHandle controller::TriggerController::node_handle_
private

Definition at line 233 of file trigger_controller.h.

double controller::TriggerController::prev_tick_
private

Definition at line 230 of file trigger_controller.h.

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

Definition at line 237 of file trigger_controller.h.

pr2_mechanism_model::RobotState* controller::TriggerController::robot_
private

Definition at line 227 of file trigger_controller.h.

ros::ServiceServer controller::TriggerController::set_waveform_handle_
private

Definition at line 232 of file trigger_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