35 #ifndef TRIGGER_CONTROLLER_H 36 #define TRIGGER_CONTROLLER_H 41 #include <ethercat_trigger_controllers/SetWaveform.h> 43 #include <std_msgs/Header.h> 44 #include <boost/scoped_ptr.hpp> 56 class TriggerControllerNode;
82 static double getTick(
double t, trigger_configuration
const &config)
84 return t * config.rep_rate - config.phase;
122 return (floor(tick) + config.phase) / config.rep_rate;
215 else if (config.pulsed)
218 return config.duty_cycle / config.rep_rate;
225 ethercat_trigger_controllers::SetWaveform::Response &resp);
boost::scoped_ptr< realtime_tools::RealtimePublisher< std_msgs::Header > > falling_edge_pub_
static double getTickDurationSec(trigger_configuration &config)
Gets the time during which the output will be active during each cycle.
static ros::Duration getTickDuration(trigger_configuration &config)
Gets the time during which the output will be active during each cycle.
static double getTick(double t, trigger_configuration const &config)
Convert time to an unrolled phase (in cycles).
pr2_hardware_interface::DigitalOutCommand * digital_out_command_
ros::NodeHandle node_handle_
ros::ServiceServer set_waveform_handle_
static double getTickStartTimeSecFromPhase(double tick, trigger_configuration const &config)
Gets the ros::Time at which a cycle starts.
boost::scoped_ptr< realtime_tools::RealtimePublisher< std_msgs::Header > > rising_edge_pub_
pr2_mechanism_model::RobotState * robot_
static ros::Time getTickStartTimeFromPhase(double tick, trigger_configuration const &config)
Gets the ros::Time at which a cycle starts.
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
std::string actuator_name_
trigger_configuration config_
ethercat_trigger_controllers::SetWaveform::Request trigger_configuration
static double getTickStartTimeSec(double time, trigger_configuration const &config)
Gets the ros::Time at which a cycle starts.
static double getTick(const ros::Time &t, trigger_configuration const &config)
Convert time to an unrolled phase (in cycles).
bool setWaveformSrv(trigger_configuration &req, ethercat_trigger_controllers::SetWaveform::Response &resp)
static ros::Time getTickStartTime(ros::Time time, trigger_configuration const &config)
Gets the ros::Time at which a cycle starts.