message_context.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2011, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  *
29  * Author: David Gossow
30  */
31 
34 
36 #include <boost/make_shared.hpp>
37 
38 #define DBG_MSG( ... ) ROS_DEBUG( __VA_ARGS__ );
39 //#define DBG_MSG( ... ) printf(" "); printf( __VA_ARGS__ ); printf("\n");
40 
41 namespace interactive_markers
42 {
43 
44 template<class MsgT>
46  tf2_ros::Buffer& tf,
47  const std::string& target_frame,
48  const typename MsgT::ConstPtr& _msg,
49  bool enable_autocomplete_transparency)
50 : tf_(tf)
51 , target_frame_(target_frame)
52 , enable_autocomplete_transparency_(enable_autocomplete_transparency)
53 {
54  // copy message, as we will be modifying it
55  msg = boost::make_shared<MsgT>( *_msg );
56 
57  init();
58 }
59 
60 template<class MsgT>
62 {
63  open_marker_idx_ = other.open_marker_idx_;
64  open_pose_idx_ = other.open_pose_idx_;
65  target_frame_ = other.target_frame_;
66  enable_autocomplete_transparency_ = other.enable_autocomplete_transparency_;
67  return *this;
68 }
69 
70 template<class MsgT>
71 bool MessageContext<MsgT>::getTransform( std_msgs::Header& header, geometry_msgs::Pose& pose_msg )
72 {
73  try
74  {
75  if ( header.frame_id != target_frame_ )
76  {
77  // get transform
78  geometry_msgs::TransformStamped transform;
79  transform = tf_.lookupTransform( target_frame_, header.frame_id, header.stamp );
80  DBG_MSG( "Transform %s -> %s at time %f is ready.", header.frame_id.c_str(), target_frame_.c_str(), header.stamp.toSec() );
81 
82  // if timestamp is given, transform message into target frame
83  if ( header.stamp != ros::Time(0) )
84  {
85  tf2::doTransform(pose_msg, pose_msg, transform);
86  ROS_DEBUG_STREAM("Changing " << header.frame_id << " to "<< target_frame_);
87  header.frame_id = target_frame_;
88  }
89  }
90  }
91  catch ( const tf2::ExtrapolationException& e )
92  {
93  ros::Time latest_time;
94  std::string error_string;
95 
96  tf_._getLatestCommonTime( tf_._lookupFrameNumber(target_frame_),
97  tf_._lookupFrameNumber(header.frame_id),
98  latest_time, &error_string );
99 
100  // if we have some tf info and it is newer than the requested time,
101  // we are very unlikely to ever receive the old tf info in the future.
102  if ( latest_time != ros::Time(0) && latest_time > header.stamp )
103  {
104  std::ostringstream s;
105  s << "The init message contains an old timestamp and cannot be transformed ";
106  s << "('" << header.frame_id << "' to '" << target_frame_
107  << "' at time " << header.stamp << ").";
108  throw InitFailException( s.str() );
109  }
110  return false;
111  }
112  return true;
113  // all other exceptions need to be handled outside
114 }
115 
116 template<class MsgT>
117 void MessageContext<MsgT>::getTfTransforms( std::vector<visualization_msgs::InteractiveMarker>& msg_vec, std::list<size_t>& indices )
118 {
119  std::list<size_t>::iterator idx_it;
120  for ( idx_it = indices.begin(); idx_it != indices.end(); )
121  {
122  visualization_msgs::InteractiveMarker& im_msg = msg_vec[ *idx_it ];
123  // transform interactive marker
124  bool success = getTransform( im_msg.header, im_msg.pose );
125  // transform regular markers
126  for ( unsigned c = 0; c<im_msg.controls.size(); c++ )
127  {
128  visualization_msgs::InteractiveMarkerControl& ctrl_msg = im_msg.controls[c];
129  for ( unsigned m = 0; m<ctrl_msg.markers.size(); m++ )
130  {
131  visualization_msgs::Marker& marker_msg = ctrl_msg.markers[m];
132  if ( !marker_msg.header.frame_id.empty() ) {
133  success = success && getTransform( marker_msg.header, marker_msg.pose );
134  }
135  }
136  }
137 
138  if ( success )
139  {
140  idx_it = indices.erase(idx_it);
141  }
142  else
143  {
144  DBG_MSG( "Transform %s -> %s at time %f is not ready.", im_msg.header.frame_id.c_str(), target_frame_.c_str(), im_msg.header.stamp.toSec() );
145  ++idx_it;
146  }
147  }
148 }
149 
150 template<class MsgT>
151 void MessageContext<MsgT>::getTfTransforms( std::vector<visualization_msgs::InteractiveMarkerPose>& msg_vec, std::list<size_t>& indices )
152 {
153  std::list<size_t>::iterator idx_it;
154  for ( idx_it = indices.begin(); idx_it != indices.end(); )
155  {
156  visualization_msgs::InteractiveMarkerPose& msg = msg_vec[ *idx_it ];
157  if ( getTransform( msg.header, msg.pose ) )
158  {
159  idx_it = indices.erase(idx_it);
160  }
161  else
162  {
163  DBG_MSG( "Transform %s -> %s at time %f is not ready.", msg.header.frame_id.c_str(), target_frame_.c_str(), msg.header.stamp.toSec() );
164  ++idx_it;
165  }
166  }
167 }
168 
169 template<class MsgT>
171 {
172  return open_marker_idx_.empty() && open_pose_idx_.empty();
173 }
174 
175 template<>
177 {
178  // mark all transforms as being missing
179  for ( size_t i=0; i<msg->markers.size(); i++ )
180  {
181  open_marker_idx_.push_back( i );
182  }
183  for ( size_t i=0; i<msg->poses.size(); i++ )
184  {
185  open_pose_idx_.push_back( i );
186  }
187  for( unsigned i=0; i<msg->markers.size(); i++ )
188  {
189  autoComplete( msg->markers[i], enable_autocomplete_transparency_ );
190  }
191  for( unsigned i=0; i<msg->poses.size(); i++ )
192  {
193  // correct empty orientation
194  if ( msg->poses[i].pose.orientation.w == 0 && msg->poses[i].pose.orientation.x == 0 &&
195  msg->poses[i].pose.orientation.y == 0 && msg->poses[i].pose.orientation.z == 0 )
196  {
197  msg->poses[i].pose.orientation.w = 1;
198  }
199  }
200 }
201 
202 template<>
204 {
205  // mark all transforms as being missing
206  for ( size_t i=0; i<msg->markers.size(); i++ )
207  {
208  open_marker_idx_.push_back( i );
209  }
210  for( unsigned i=0; i<msg->markers.size(); i++ )
211  {
212  autoComplete( msg->markers[i], enable_autocomplete_transparency_ );
213  }
214 }
215 
216 template<>
218 {
219  getTfTransforms( msg->markers, open_marker_idx_ );
220  getTfTransforms( msg->poses, open_pose_idx_ );
221  if ( isReady() )
222  {
223  DBG_MSG( "Update message with seq_num=%lu is ready.", msg->seq_num );
224  }
225 }
226 
227 template<>
229 {
230  getTfTransforms( msg->markers, open_marker_idx_ );
231  if ( isReady() )
232  {
233  DBG_MSG( "Init message with seq_num=%lu is ready.", msg->seq_num );
234  }
235 }
236 
237 // explicit template instantiation
240 
241 
242 }
243 
244 
interactive_markers::MessageContext::getTfTransforms
void getTfTransforms()
interactive_markers::InitFailException
Definition: message_context.h:84
interactive_markers::MessageContext::msg
MsgT::Ptr msg
Definition: message_context.h:62
interactive_markers::autoComplete
INTERACTIVE_MARKERS_PUBLIC void autoComplete(visualization_msgs::InteractiveMarker &msg, bool enable_autocomplete_transparency=true)
fill in default values & insert default controls when none are specified.
Definition: tools.cpp:44
interactive_markers::MessageContext::enable_autocomplete_transparency_
bool enable_autocomplete_transparency_
Definition: message_context.h:81
s
XmlRpcServer s
interactive_markers::MessageContext::target_frame_
std::string target_frame_
Definition: message_context.h:80
interactive_markers::MessageContext::open_pose_idx_
std::list< size_t > open_pose_idx_
Definition: message_context.h:78
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
interactive_markers::MessageContext::isReady
bool isReady()
Definition: message_context.cpp:170
interactive_markers::MessageContext::open_marker_idx_
std::list< size_t > open_marker_idx_
Definition: message_context.h:77
tf2::ExtrapolationException
interactive_markers::MessageContext::getTransform
bool getTransform(std_msgs::Header &header, geometry_msgs::Pose &pose_msg)
Definition: message_context.cpp:71
tf2_ros::Buffer
interactive_markers::MessageContext::MessageContext
MessageContext(tf2_ros::Buffer &tf, const std::string &target_frame, const typename MsgT::ConstPtr &msg, bool enable_autocomplete_transparency=true)
Definition: message_context.cpp:45
interactive_markers::MessageContext
Definition: message_context.h:49
ros::Time
tf2::doTransform
void doTransform(const T &data_in, T &data_out, const geometry_msgs::TransformStamped &transform)
interactive_markers::MessageContext::operator=
MessageContext< MsgT > & operator=(const MessageContext< MsgT > &other)
Definition: message_context.cpp:61
interactive_markers::MessageContext::init
void init()
tf2_geometry_msgs.h
target_frame
std::string target_frame
Definition: client_test.cpp:72
interactive_markers
Definition: message_context.h:45
tools.h
header
const std::string header
message_context.h
DBG_MSG
#define DBG_MSG(...)
Definition: message_context.cpp:38


interactive_markers
Author(s): David Gossow, William Woodall
autogenerated on Fri Oct 27 2023 02:31:54