Skip to content

Commit

Permalink
Merge pull request #20 from ros/message_event
Browse files Browse the repository at this point in the history
replace usage of __connection_header with MessageEvent (#17)
  • Loading branch information
dirk-thomas committed Feb 14, 2014
2 parents 1c62756 + 856fe22 commit bbd06ca
Show file tree
Hide file tree
Showing 3 changed files with 19 additions and 15 deletions.
28 changes: 17 additions & 11 deletions include/actionlib/client/action_client.h
Original file line number Diff line number Diff line change
Expand Up @@ -243,31 +243,37 @@ class ActionClient
}

template<class M, class T>
ros::Subscriber queue_subscribe(const std::string& topic, uint32_t queue_size, void(T::*fp)(const boost::shared_ptr<M const>&), T* obj, ros::CallbackQueueInterface* queue)
ros::Subscriber queue_subscribe(const std::string& topic, uint32_t queue_size, void(T::*fp)(const ros::MessageEvent<M const>&), T* obj, ros::CallbackQueueInterface* queue)
{
ros::SubscribeOptions ops;
ops.init<M>(topic, queue_size, boost::bind(fp, obj, _1));
ops.transport_hints = ros::TransportHints();
ops.callback_queue = queue;
ops.topic = topic;
ops.queue_size = queue_size;
ops.md5sum = ros::message_traits::md5sum<M>();
ops.datatype = ros::message_traits::datatype<M>();
ops.helper = ros::SubscriptionCallbackHelperPtr(
new ros::SubscriptionCallbackHelperT<const ros::MessageEvent<M const>& >(
boost::bind(fp, obj, _1)
)
);
return n_.subscribe(ops);
}

void statusCb(const actionlib_msgs::GoalStatusArrayConstPtr& status_array)
void statusCb(const ros::MessageEvent<actionlib_msgs::GoalStatusArray const>& status_array_event)
{
ROS_DEBUG_NAMED("actionlib", "Getting status over the wire.");
if (connection_monitor_)
connection_monitor_->processStatus(status_array);
manager_.updateStatuses(status_array);
connection_monitor_->processStatus(status_array_event.getConstMessage(), status_array_event.getPublisherName());
manager_.updateStatuses(status_array_event.getConstMessage());
}

void feedbackCb(const ActionFeedbackConstPtr& action_feedback)
void feedbackCb(const ros::MessageEvent<ActionFeedback const>& action_feedback)
{
manager_.updateFeedbacks(action_feedback);
manager_.updateFeedbacks(action_feedback.getConstMessage());
}

void resultCb(const ActionResultConstPtr& action_result)
void resultCb(const ros::MessageEvent<ActionResult const>& action_result)
{
manager_.updateResults(action_result);
manager_.updateResults(action_result.getConstMessage());
}
};

Expand Down
2 changes: 1 addition & 1 deletion include/actionlib/client/connection_monitor.h
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ class ACTIONLIB_DECL ConnectionMonitor

void cancelDisconnectCallback(const ros::SingleSubscriberPublisher& pub);

void processStatus(const actionlib_msgs::GoalStatusArrayConstPtr& status);
void processStatus(const actionlib_msgs::GoalStatusArrayConstPtr& status, const std::string& caller_id);

bool waitForActionServerToStart(const ros::Duration& timeout = ros::Duration(0,0), const ros::NodeHandle& nh = ros::NodeHandle() );
bool isServerConnected();
Expand Down
4 changes: 1 addition & 3 deletions src/connection_monitor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -162,12 +162,10 @@ string ConnectionMonitor::cancelSubscribersString()
}

// ********* GoalStatus Connections *********
void ConnectionMonitor::processStatus(const actionlib_msgs::GoalStatusArrayConstPtr& status)
void ConnectionMonitor::processStatus(const actionlib_msgs::GoalStatusArrayConstPtr& status, const std::string& cur_status_caller_id)
{
boost::recursive_mutex::scoped_lock lock(data_mutex_);

string cur_status_caller_id = (*(status->__connection_header))["callerid"];

if (status_received_)
{
if (status_caller_id_ != cur_status_caller_id)
Expand Down

0 comments on commit bbd06ca

Please sign in to comment.