$search
#include <trigger_controller.h>
Public Member Functions | |
bool | init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n) |
TriggerController () | |
void | update () |
~TriggerController () | |
Static Public Member Functions | |
static double | getTick (const ros::Time &t, trigger_configuration const &config) |
Convert time to an unrolled phase (in cycles). | |
static double | getTick (double t, trigger_configuration const &config) |
Convert time to an unrolled phase (in cycles). | |
static ros::Duration | getTickDuration (trigger_configuration &config) |
Gets the time during which the output will be active during each cycle. | |
static double | getTickDurationSec (trigger_configuration &config) |
Gets the time during which the output will be active during each cycle. | |
static ros::Time | getTickStartTime (ros::Time time, trigger_configuration const &config) |
Gets the ros::Time at which a cycle starts. | |
static ros::Time | getTickStartTimeFromPhase (double tick, trigger_configuration const &config) |
Gets the ros::Time at which a cycle starts. | |
static double | getTickStartTimeSec (double time, trigger_configuration const &config) |
Gets the ros::Time at which a cycle starts. | |
static double | getTickStartTimeSecFromPhase (double tick, trigger_configuration const &config) |
Gets the ros::Time at which a cycle starts. | |
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::DigitalOutCommand * | digital_out_command_ |
boost::scoped_ptr < realtime_tools::RealtimePublisher < roslib::Header > > | falling_edge_pub_ |
bool | last_out_ |
ros::NodeHandle | node_handle_ |
double | prev_tick_ |
boost::scoped_ptr < realtime_tools::RealtimePublisher < roslib::Header > > | rising_edge_pub_ |
pr2_mechanism_model::RobotState * | robot_ |
ros::ServiceServer | set_waveform_handle_ |
Definition at line 58 of file trigger_controller.h.
TriggerController::TriggerController | ( | ) |
Definition at line 69 of file trigger_controller.cpp.
TriggerController::~TriggerController | ( | ) |
Definition at line 74 of file trigger_controller.cpp.
double TriggerController::getTick | ( | ) | [private] |
Definition at line 78 of file trigger_controller.cpp.
static double controller::TriggerController::getTick | ( | const ros::Time & | t, | |
trigger_configuration const & | config | |||
) | [inline, static] |
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.
t | Time for which the phase should be evaluated. | |
config | Trigger configuration for which the phase should be evaluated. |
Definition at line 101 of file trigger_controller.h.
static double controller::TriggerController::getTick | ( | double | t, | |
trigger_configuration const & | config | |||
) | [inline, static] |
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.
t | Time for which the phase should be evaluated. | |
config | Trigger configuration for which the phase should be evaluated. |
Definition at line 82 of file trigger_controller.h.
static ros::Duration controller::TriggerController::getTickDuration | ( | trigger_configuration & | config | ) | [inline, static] |
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.
config | Trigger configuration for which the cycle start should be evaluated. |
Definition at line 194 of file trigger_controller.h.
static double controller::TriggerController::getTickDurationSec | ( | trigger_configuration & | config | ) | [inline, static] |
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.
config | Trigger configuration for which the cycle start should be evaluated. |
Definition at line 211 of file trigger_controller.h.
static ros::Time controller::TriggerController::getTickStartTime | ( | ros::Time | time, | |
trigger_configuration const & | config | |||
) | [inline, static] |
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.
tick | Time for which to perform the computation. | |
config | Trigger configuration for which the cycle start should be evaluated. |
Definition at line 158 of file trigger_controller.h.
static ros::Time controller::TriggerController::getTickStartTimeFromPhase | ( | double | tick, | |
trigger_configuration const & | config | |||
) | [inline, static] |
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.
tick | Unrolled phase. | |
config | Trigger configuration for which the cycle start should be evaluated. |
Definition at line 139 of file trigger_controller.h.
static double controller::TriggerController::getTickStartTimeSec | ( | double | time, | |
trigger_configuration const & | config | |||
) | [inline, static] |
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.
tick | Time for which to perform the computation. | |
config | Trigger configuration for which the cycle start should be evaluated. |
Definition at line 177 of file trigger_controller.h.
static double controller::TriggerController::getTickStartTimeSecFromPhase | ( | double | tick, | |
trigger_configuration const & | config | |||
) | [inline, static] |
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.
tick | Unrolled phase. | |
config | Trigger configuration for which the cycle start should be evaluated. |
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.
std::string controller::TriggerController::actuator_name_ [private] |
Definition at line 242 of file trigger_controller.h.
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< roslib::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.
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< roslib::Header> > controller::TriggerController::rising_edge_pub_ [private] |
Definition at line 237 of file trigger_controller.h.
Definition at line 227 of file trigger_controller.h.
Definition at line 232 of file trigger_controller.h.