36 #include <boost/format.hpp> 52 MultiTriggerController::~MultiTriggerController()
96 std::string param_value;
98 std::stringstream parser(param_value);
100 while (parser >> value)
101 rslt.push_back(value);
103 bool eof = parser.eof();
106 ROS_ERROR(
"Error parsing '%s/%s' argument to MultiTriggerController.", nh.
getNamespace().c_str(), param.c_str());
115 ROS_DEBUG(
"LOADING TRIGGER CONTROLLER NODE");
122 ROS_DEBUG(
"MultiTriggerController::init starting");
127 ROS_ERROR(
"MultiTriggerController was not given a digital_output parameter.");
134 ROS_ERROR(
"MultiTriggerController could not find digital output named \"%s\".",
144 std::vector<string> topics;
145 std::vector<double> times;
146 std::vector<uint32_t> values;
152 if (times.size() != topics.size() || times.size() != values.size())
153 ROS_ERROR(
"'topics', 'times' and 'values' parameters must have same length in %s. Ignoring initial settings.",
157 for (
unsigned int i = 0; i < times.size(); i++)
159 ethercat_trigger_controllers::MultiWaveformTransition t;
163 config_.transitions.push_back(t);
166 ethercat_trigger_controllers::SetMultiWaveform::Request req;
168 ethercat_trigger_controllers::SetMultiWaveform::Response dummy;
175 ROS_DEBUG(
"MultiTriggerController::init completed successfully.");
181 ethercat_trigger_controllers::SetMultiWaveform::Request &req,
182 ethercat_trigger_controllers::SetMultiWaveform::Response &resp)
184 std::vector<boost::shared_ptr<realtime_tools::RealtimePublisher<std_msgs::Header> > > new_pubs;
185 new_pubs.reserve(
config_.transitions.size());
186 ethercat_trigger_controllers::MultiWaveform &new_config = req.waveform;
188 double prev_time = -1;
190 double new_transition_period = round((now - new_config.zero_offset) / new_config.period);
191 double current_period_start = new_config.zero_offset + new_transition_period * new_config.period;
192 double now_offset = now - current_period_start;
193 unsigned int new_transition_index = 0;
196 if (new_transition_period <= 0)
198 resp.status_message =
"MultiTrigger period must be >0.";
199 resp.success =
false;
202 for (std::vector<ethercat_trigger_controllers::MultiWaveformTransition>::iterator trans = new_config.transitions.begin();
203 trans != new_config.transitions.end() && resp.success; trans++)
205 if (trans->time < now_offset)
206 new_transition_index++;
208 if (trans->time < 0 || trans->time >= new_config.period)
210 resp.status_message = (boost::format(
"MultiTriggerController::setMultiWaveformSrv transition time (%f) must be >= 0 and < period (%f).")%
211 trans->time%new_config.period).str();
212 resp.success =
false;
215 if (prev_time >= trans->time)
217 resp.status_message = (boost::format(
"MultiTriggerController::setMultiWaveformSrv transition times must be in increasing order. %f >= %f")%
218 prev_time%trans->time).str();
219 resp.success =
false;
223 if (new_transition_index == new_config.transitions.size())
225 new_transition_index = 0;
226 new_transition_period++;
229 double new_transition_time = current_period_start + new_config.transitions[new_transition_index].time;
237 for (std::vector<ethercat_trigger_controllers::MultiWaveformTransition>::iterator trans = new_config.transitions.begin();
238 trans != new_config.transitions.end() && resp.success; trans++)
242 if (trans->topic.compare(
"-"))
245 new_pubs.push_back(new_pub);
257 ROS_ERROR(
"%s", resp.status_message.c_str());
std::string digital_output_name_
unsigned int transition_index_
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle node_handle_
pr2_mechanism_model::RobotState * robot_
std::vector< boost::shared_ptr< realtime_tools::RealtimePublisher< std_msgs::Header > > > pubs_
pr2_hardware_interface::HardwareInterface * hw_
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
DigitalOut * getDigitalOut(const std::string &name) const
boost::mutex config_mutex_
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
PLUGINLIB_EXPORT_CLASS(pr2_mechanism_model::PR2BeltCompensatorTransmission, pr2_mechanism_model::Transmission) namespace pr2_mechanism_model
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
const std::string & getNamespace() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::ServiceServer set_waveform_handle_
pr2_hardware_interface::DigitalOutCommand * digital_out_command_
bool getParam(const std::string &key, std::string &s) const
double transition_period_
static bool parseParamList(ros::NodeHandle nh, std::string param, std::vector< T > &rslt)
DigitalOutCommand command_
bool setMultiWaveformSrv(ethercat_trigger_controllers::SetMultiWaveform::Request &req, ethercat_trigger_controllers::SetMultiWaveform::Response &resp)