Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 2 additions & 1 deletion src/interactive_marker_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -281,7 +281,8 @@ void InteractiveMarkerClient::processUpdate(
update_queue_.pop_back();
}

update_queue_.push_front(UpdateMessageContext(
update_queue_.push_front(
UpdateMessageContext(
tf_buffer_core_, target_frame_, msg, enable_autocomplete_transparency_));
}

Expand Down
12 changes: 8 additions & 4 deletions src/interactive_marker_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -405,7 +405,8 @@ void InteractiveMarkerServer::processFeedback(
if (marker_context.last_client_id != feedback->client_id &&
(clock_->now() - marker_context.last_feedback).seconds() < 1.0)
{
RCLCPP_DEBUG(logger_, "Rejecting feedback for %s: conflicting feedback from separate clients.",
RCLCPP_DEBUG(
logger_, "Rejecting feedback for %s: conflicting feedback from separate clients.",
feedback->marker_name.c_str());
return;
}
Expand All @@ -416,11 +417,13 @@ void InteractiveMarkerServer::processFeedback(
if (feedback->event_type == visualization_msgs::msg::InteractiveMarkerFeedback::POSE_UPDATE) {
if (marker_context.int_marker.header.stamp == rclcpp::Time()) {
// keep the old header
doSetPose(pending_updates_.find(
doSetPose(
pending_updates_.find(
feedback->marker_name), feedback->marker_name, feedback->pose,
marker_context.int_marker.header);
} else {
doSetPose(pending_updates_.find(
doSetPose(
pending_updates_.find(
feedback->marker_name), feedback->marker_name, feedback->pose, feedback->header);
}
}
Expand Down Expand Up @@ -465,7 +468,8 @@ void InteractiveMarkerServer::doSetPose(

update_it->second.int_marker.pose = pose;
update_it->second.int_marker.header = header;
RCLCPP_DEBUG(logger_, "Marker '%s' is now at %f, %f, %f",
RCLCPP_DEBUG(
logger_, "Marker '%s' is now at %f, %f, %f",
update_it->first.c_str(), pose.position.x, pose.position.y, pose.position.z);
}

Expand Down
3 changes: 2 additions & 1 deletion src/menu_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,8 @@
#define RCUTILS_ASSERT_MSG(cond, ...) \
do { \
if (!(cond)) { \
RCUTILS_LOG_FATAL("ASSERTION FAILED\n\tfile = %s\n\tline = %d\n\tcond = %s\n\tmessage = ", \
RCUTILS_LOG_FATAL( \
"ASSERTION FAILED\n\tfile = %s\n\tline = %d\n\tcond = %s\n\tmessage = ", \
__FILE__, __LINE__, #cond); \
RCUTILS_LOG_FATAL(__VA_ARGS__); \
RCUTILS_LOG_FATAL("\n"); \
Expand Down
9 changes: 6 additions & 3 deletions src/message_context.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,8 @@ bool MessageContext<MsgT>::getTransform(
// get transform
geometry_msgs::msg::TransformStamped transform = tf_buffer_core_->lookupTransform(
target_frame_, header.frame_id, tf2::timeFromSec(rclcpp::Time(header.stamp).seconds()));
RCUTILS_LOG_DEBUG("Transform %s -> %s at time %f is ready.",
RCUTILS_LOG_DEBUG(
"Transform %s -> %s at time %f is ready.",
header.frame_id.c_str(), target_frame_.c_str(), rclcpp::Time(header.stamp).seconds());

// if timestamp is given, transform message into target frame
Expand Down Expand Up @@ -146,7 +147,8 @@ void MessageContext<MsgT>::getTfTransforms(
if (success) {
idx_it = indices.erase(idx_it);
} else {
RCUTILS_LOG_DEBUG("Transform %s -> %s at time %f is not ready.",
RCUTILS_LOG_DEBUG(
"Transform %s -> %s at time %f is not ready.",
im_msg.header.frame_id.c_str(), target_frame_.c_str(), rclcpp::Time(
im_msg.header.stamp).seconds());
++idx_it;
Expand All @@ -165,7 +167,8 @@ void MessageContext<MsgT>::getTfTransforms(
if (getTransform(msg.header, msg.pose)) {
idx_it = indices.erase(idx_it);
} else {
RCUTILS_LOG_DEBUG("Transform %s -> %s at time %f is not ready.",
RCUTILS_LOG_DEBUG(
"Transform %s -> %s at time %f is not ready.",
msg.header.frame_id.c_str(), target_frame_.c_str(), rclcpp::Time(
msg.header.stamp).seconds());
++idx_it;
Expand Down
3 changes: 2 additions & 1 deletion test/interactive_markers/timed_expect.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,8 @@
* \param func The optional function to call.
*/
#define TIMED_EXPECT_EQ(...) \
EXPAND(TIMED_EXPECT_EQ_CHOOSER( \
EXPAND( \
TIMED_EXPECT_EQ_CHOOSER( \
__VA_ARGS__, \
TIMED_EXPECT_EQ_6_ARGS(__VA_ARGS__, UNUSED), \
TIMED_EXPECT_EQ_5_ARGS(__VA_ARGS__, UNUSED), \
Expand Down