35 #ifndef TRIGGER_CONTROLLER_H 36 #define TRIGGER_CONTROLLER_H 41 #include <ethercat_trigger_controllers/SetMultiWaveform.h> 42 #include <ethercat_trigger_controllers/MultiWaveform.h> 44 #include <std_msgs/Header.h> 45 #include <boost/scoped_ptr.hpp> 57 typedef ethercat_trigger_controllers::MultiWaveform
config_t;
71 ethercat_trigger_controllers::SetMultiWaveform::Request &req,
72 ethercat_trigger_controllers::SetMultiWaveform::Response &resp);
86 std::vector<boost::shared_ptr<realtime_tools::RealtimePublisher<std_msgs::Header> > >
pubs_;
std::string digital_output_name_
unsigned int transition_index_
ethercat_trigger_controllers::MultiWaveform config_t
ros::NodeHandle node_handle_
pr2_mechanism_model::RobotState * robot_
std::vector< boost::shared_ptr< realtime_tools::RealtimePublisher< std_msgs::Header > > > pubs_
boost::mutex config_mutex_
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
~MultiTriggerController()
ros::ServiceServer set_waveform_handle_
pr2_hardware_interface::DigitalOutCommand * digital_out_command_
double transition_period_
bool setMultiWaveformSrv(ethercat_trigger_controllers::SetMultiWaveform::Request &req, ethercat_trigger_controllers::SetMultiWaveform::Response &resp)