21 #define _USE_MATH_DEFINES
52 std::lock_guard<std::mutex> lock(m_mutex);
53 if (
id >= 0 && (
size_t)
id < m_transforms.size())
55 m_transforms.erase(m_transforms.begin() +
id);
63 std::lock_guard<std::mutex> lock(m_mutex);
64 for (
auto& m_transform : m_transforms)
67 if (m_transform.dst_frame_id ==
t.dst_frame_id && m_transform.src_frame_id ==
t.src_frame_id)
76 m_transforms.push_back(
t);
82 std::lock_guard<std::mutex> lock(m_mutex);
83 if (t1==
"*" && t2==
"*")
91 for (
size_t i = 0; i < m_transforms.size(); )
94 if (m_transforms[i].dst_frame_id == t2)
96 m_transforms.erase(m_transforms.begin() + i);
109 for (
size_t i = 0; i < m_transforms.size(); )
112 if (m_transforms[i].src_frame_id == t1)
114 m_transforms.erase(m_transforms.begin() + i);
126 for (
size_t i = 0; i < m_transforms.size(); i++)
128 if ((m_transforms[i].dst_frame_id == t1 && m_transforms[i].src_frame_id == t2) ||
129 (m_transforms[i].dst_frame_id == t2 && m_transforms[i].src_frame_id == t1) )
131 m_transforms.erase(m_transforms.begin() + i);
141 std::lock_guard<std::mutex> lock(m_mutex);
142 m_transforms.clear();
152 m_enable_publish_ros_tf =
false;
153 m_enable_subscribe_ros_tf =
false;
154 m_yarp_static_transform_storage =
nullptr;
155 m_yarp_timed_transform_storage =
nullptr;
156 m_ros_static_transform_storage =
nullptr;
157 m_ros_timed_transform_storage =
nullptr;
159 m_FrameTransformTimeout = 0.200;
165 if (m_yarp_static_transform_storage)
167 delete m_yarp_static_transform_storage;
168 m_yarp_static_transform_storage =
nullptr;
170 if (m_yarp_timed_transform_storage)
172 delete m_yarp_timed_transform_storage;
173 m_yarp_timed_transform_storage =
nullptr;
175 if (m_ros_timed_transform_storage)
177 delete m_ros_timed_transform_storage;
178 m_ros_timed_transform_storage =
nullptr;
180 if (m_ros_static_transform_storage)
182 delete m_ros_static_transform_storage;
183 m_ros_static_transform_storage =
nullptr;
189 std::vector<Transforms_server_storage*> storages;
190 std::vector<string> storageDescription;
191 storages.push_back(m_ros_timed_transform_storage);
192 storageDescription.emplace_back(
"ros timed transforms");
194 storages.push_back(m_ros_static_transform_storage);
195 storageDescription.emplace_back(
"ros static transforms");
197 storages.push_back(m_yarp_timed_transform_storage);
198 storageDescription.emplace_back(
"yarp timed transforms");
200 storages.push_back(m_yarp_static_transform_storage);
201 storageDescription.emplace_back(
"yarp static transforms");
203 if (storages[0]->size() == 0 &&
204 storages[1]->size() == 0 &&
205 storages[2]->size() == 0 &&
206 storages[3]->size() == 0)
212 for(
size_t s = 0; s < storages.size(); s++ )
219 std::string text_to_print = storageDescription[s] + std::string(
"(") +std::to_string(storages[s]->size())+ std::string(
"): ");
222 for(
size_t i = 0; i < storages[s]->size(); i++)
232 if (m_show_transforms_in_diagram==do_not_show)
236 else if (m_show_transforms_in_diagram==show_quaternion)
238 return string(
",label=\" ") + (*storage)[i].toString(FrameTransform::display_transform_mode_t::rotation_as_quaternion) +
"\"";
240 else if (m_show_transforms_in_diagram == show_matrix)
242 return string(
",label=\" ") + (*storage)[i].toString(FrameTransform::display_transform_mode_t::rotation_as_matrix) +
"\"";
244 else if (m_show_transforms_in_diagram == show_rpy)
246 return string(
",label=\" ") + (*storage)[i].toString(FrameTransform::display_transform_mode_t::rotation_as_rpy) +
"\"";
249 yCError(FRAMETRANSFORMSERVER) <<
"get_matrix_as_text() invalid option";
260 bool FrameTransformServer::generate_view()
262 string dot_string =
"digraph G { ";
263 for (
size_t i = 0; i < m_ros_timed_transform_storage->
size(); i++)
265 string edge_text = get_matrix_as_text(m_ros_timed_transform_storage, i);
266 string trf_text = (*m_ros_timed_transform_storage)[i].src_frame_id +
"->" +
267 (*m_ros_timed_transform_storage)[i].dst_frame_id +
" " +
269 dot_string += trf_text +
'\n';
271 for (
size_t i = 0; i < m_ros_static_transform_storage->
size(); i++)
273 string edge_text = get_matrix_as_text(m_ros_static_transform_storage,i);
274 string trf_text = (*m_ros_static_transform_storage)[i].src_frame_id +
"->" +
275 (*m_ros_static_transform_storage)[i].dst_frame_id +
" " +
276 "[color = black, style=dashed "+ edge_text +
"]";
277 dot_string += trf_text +
'\n';
279 for (
size_t i = 0; i < m_yarp_timed_transform_storage->
size(); i++)
281 string edge_text = get_matrix_as_text(m_yarp_timed_transform_storage, i);
282 string trf_text = (*m_yarp_timed_transform_storage)[i].src_frame_id +
"->" +
283 (*m_yarp_timed_transform_storage)[i].dst_frame_id +
" " +
284 "[color = blue "+ edge_text +
"]";
285 dot_string += trf_text +
'\n';
287 for (
size_t i = 0; i < m_yarp_static_transform_storage->
size(); i++)
289 string edge_text = get_matrix_as_text(m_yarp_static_transform_storage, i);
290 string trf_text = (*m_yarp_static_transform_storage)[i].src_frame_id +
"->" +
291 (*m_yarp_static_transform_storage)[i].dst_frame_id +
" " +
292 "[color = blue, style=dashed " + edge_text +
"]";
293 dot_string += trf_text +
'\n';
298 node[shape=plaintext]\n\
299 subgraph cluster_01 {\n\
300 label = \"Legend\";\n\
301 key[label=<<table border=\"0\" cellpadding=\"2\" cellspacing=\"0\" cellborder=\"0\">\n\
302 <tr><td align=\"right\" port=\"i1\">YARP timed transform</td></tr>\n\
303 <tr><td align=\"right\" port=\"i2\">YARP static transform</td></tr>\n\
304 <tr><td align=\"right\" port=\"i3\">ROS timed transform</td></tr>\n\
305 <tr><td align=\"right\" port=\"i4\">ROS static transform</td></tr>\n\
307 key2[label=<<table border=\"0\" cellpadding=\"2\" cellspacing=\"0\" cellborder=\"0\">\n\
308 <tr><td port = \"i1\"> </td></tr>\n\
309 <tr><td port = \"i2\"> </td></tr>\n\
310 <tr><td port = \"i3\"> </td></tr>\n\
311 <tr><td port = \"i4\"> </td></tr>\n\
313 key:i1:e -> key2:i1:w [color = blue]\n\
314 key:i2:e -> key2:i2:w [color = blue, style=dashed]\n\
315 key:i3:e -> key2:i3:w [color = black]\n\
316 key:i4:e -> key2:i4:w [color = black, style=dashed]\n\
319 string command_string =
"printf '"+dot_string+ legend +
"' | dot -Tpdf > frames.pdf";
320 #if defined (__linux__)
321 int ret = std::system(
"dot -V");
324 yCError(FRAMETRANSFORMSERVER) <<
"dot executable not found. Please install graphviz.";
328 yCDebug(FRAMETRANSFORMSERVER) <<
"Command string is:" << command_string;
329 ret = std::system(command_string.c_str());
332 yCError(FRAMETRANSFORMSERVER) <<
"The following command failed to execute:" << command_string;
336 yCError(FRAMETRANSFORMSERVER) <<
"Not yet implemented. Available only Linux";
344 std::lock_guard<std::mutex> lock(m_mutex);
347 bool ok = in.
read(connection);
348 if (!ok)
return false;
362 yCError(FRAMETRANSFORMSERVER) <<
"read(): Protocol error";
399 yCError(FRAMETRANSFORMSERVER) <<
"read(): Something strange happened";
405 m_yarp_timed_transform_storage->
clear();
406 m_yarp_static_transform_storage->
clear();
407 m_ros_timed_transform_storage->
clear();
408 m_ros_static_transform_storage->
clear();
416 bool ret1 = m_yarp_timed_transform_storage->
delete_transform(frame1, frame2);
424 bool ret2 = m_yarp_static_transform_storage->
delete_transform(frame1, frame2);
435 yCError(FRAMETRANSFORMSERVER,
"Invalid vocab received");
440 else if(request ==
"help")
443 out.
addString(
"'list': get all transforms stored");
444 out.
addString(
"'delete_all': delete all transforms");
445 out.
addString(
"'set_static_transform_rad <src> <dst> <x> <y> <z> <roll> <pitch> <yaw>': create a static transform (angles in radians)");
446 out.
addString(
"'set_static_transform_deg <src> <dst> <x> <y> <z> <roll> <pitch> <yaw>': create a static transform (angles in degrees)");
447 out.
addString(
"'delete_static_transform <src> <dst>': delete a static transform");
448 out.
addString(
"'generate_view <option>': generate a frames.pdf file showing the transform tree diagram.");
449 out.
addString(
" The following values are valid for option (default=none)");
450 out.
addString(
" 'show_rpy': show roation as rpy angles");
451 out.
addString(
" 'show_quaterion:'show rotation as a quaternion");
452 out.
addString(
" 'show_matrix:'show rotationa as a 3x3 rotation matrix");
454 else if (request ==
"set_static_transform_rad" ||
455 request ==
"set_static_transform_deg")
463 if (request ==
"set_static_transform_rad")
465 else if (request ==
"set_static_transform_deg")
471 yCInfo(FRAMETRANSFORMSERVER) <<
"set_static_transform done";
472 out.
addString(
"set_static_transform done");
476 yCError(FRAMETRANSFORMSERVER) <<
"read(): something strange happened";
479 else if(request ==
"delete_all")
481 m_yarp_timed_transform_storage->
clear();
482 m_yarp_static_transform_storage->
clear();
483 m_ros_timed_transform_storage->
clear();
484 m_ros_static_transform_storage->
clear();
485 yCInfo(FRAMETRANSFORMSERVER) <<
"delete_all done";
488 else if (request ==
"list")
493 else if (request ==
"generate_view")
495 m_show_transforms_in_diagram = do_not_show;
496 if (in.
get(1).
asString() ==
"show_quaternion") m_show_transforms_in_diagram = show_quaternion;
497 else if (in.
get(1).
asString() ==
"show_matrix") m_show_transforms_in_diagram = show_matrix;
498 else if (in.
get(1).
asString() ==
"show_rpy") m_show_transforms_in_diagram = show_rpy;
502 else if (request ==
"delete_static_transform")
508 out.
addString(
"delete_static_transform done");
512 yCError(FRAMETRANSFORMSERVER,
"Invalid vocab received");
518 if (returnToSender !=
nullptr)
520 out.
write(*returnToSender);
524 yCError(FRAMETRANSFORMSERVER) <<
"Invalid return to sender";
532 if (!m_rpcPort.
open(m_rpcPortName))
534 yCError(FRAMETRANSFORMSERVER,
"Failed to open port %s", m_rpcPortName.c_str());
540 if (!m_streamingPort.
open(m_streamingPortName))
542 yCError(FRAMETRANSFORMSERVER,
"Failed to open port %s", m_streamingPortName.c_str());
547 if (m_enable_publish_ros_tf)
549 if (m_rosNode ==
nullptr)
555 yCError(FRAMETRANSFORMSERVER) <<
"Unable to publish data on " <<
ROSTOPICNAME_TF <<
" topic, check your yarp-ROS network configuration";
560 yCError(FRAMETRANSFORMSERVER) <<
"Unable to publish data on " <<
ROSTOPICNAME_TF_STATIC <<
" topic, check your yarp-ROS network configuration";
566 if (m_enable_subscribe_ros_tf)
568 if (m_rosNode ==
nullptr)
574 yCError(FRAMETRANSFORMSERVER) <<
"Unable to subscribe to " <<
ROSTOPICNAME_TF <<
" topic, check your yarp-ROS network configuration";
577 m_rosSubscriberPort_tf_timed.
setStrict();
583 m_rosSubscriberPort_tf_static.
setStrict();
592 yCInfo(FRAMETRANSFORMSERVER) <<
"Transform server started";
599 if (config.
check(
"USER_TF"))
604 for (
size_t i = 0; i < all_transforms_group.
size(); i++)
611 yCError(FRAMETRANSFORMSERVER) <<
"No entries in USER_TF group";
620 for(
int i = 0; i < 16; i++)
624 yCError(FRAMETRANSFORMSERVER) <<
"transformServer: element " << i <<
" is not a double.";
640 yCError(FRAMETRANSFORMSERVER) <<
"transformServer: param not correct.. for the 4x4 matrix mode" <<
641 "you must provide 18 parameter. the matrix, the source frame(string) and the destination frame(string)";
649 else if( b->
size() == 8 &&
666 yCError(FRAMETRANSFORMSERVER) <<
"transformServer: param not correct.. a tf requires 8 param in the format:" <<
667 "x(dbl) y(dbl) z(dbl) r(dbl) p(dbl) y(dbl) src(str) dst(str)";
673 yCInfo(FRAMETRANSFORMSERVER) <<
"Transform from" <<
t.src_frame_id <<
"to" <<
t.dst_frame_id <<
"successfully set";
677 yCInfo(FRAMETRANSFORMSERVER) <<
"Unbale to set transform from " <<
t.src_frame_id <<
"to" <<
t.dst_frame_id;
684 yCInfo(FRAMETRANSFORMSERVER) <<
"No starting tf found";
694 if (!config.
check(
"period"))
700 m_period = config.
find(
"period").
asInt32() / 1000.0;
701 yCInfo(FRAMETRANSFORMSERVER) <<
"Thread period set to:" << m_period;
704 if (config.
check(
"transforms_lifetime"))
706 m_FrameTransformTimeout = config.
find(
"transforms_lifetime").
asFloat64();
707 yCInfo(FRAMETRANSFORMSERVER) <<
"transforms_lifetime set to:" << m_FrameTransformTimeout;
711 if (!config.
check(
"name"))
713 name =
"transformServer";
719 m_streamingPortName =
"/"+ name +
"/transforms:o";
720 m_rpcPortName =
"/" + name +
"/rpc";
723 if (!config.
check(
"ROS"))
725 yCError(FRAMETRANSFORMSERVER) <<
"Missing ROS group";
729 if (ROS_config.
check(
"enable_ros_publisher") ==
false)
731 yCError(FRAMETRANSFORMSERVER) <<
"Missing 'enable_ros_publisher' in ROS group";
734 if (ROS_config.
find(
"enable_ros_publisher").
asInt32() == 1 || ROS_config.
find(
"enable_ros_publisher").
asString() ==
"true")
736 m_enable_publish_ros_tf =
true;
737 yCInfo(FRAMETRANSFORMSERVER) <<
"Enabled ROS publisher";
739 if (ROS_config.
check(
"enable_ros_subscriber") ==
false)
741 yCError(FRAMETRANSFORMSERVER) <<
"Missing 'enable_ros_subscriber' in ROS group";
744 if (ROS_config.
find(
"enable_ros_subscriber").
asInt32() == 1 || ROS_config.
find(
"enable_ros_subscriber").
asString() ==
"true")
746 m_enable_subscribe_ros_tf =
true;
747 yCInfo(FRAMETRANSFORMSERVER) <<
"Enabled ROS subscriber";
753 parseStartingTf(config);
761 m_streamingPort.
close();
764 if (m_enable_publish_ros_tf)
767 m_rosPublisherPort_tf_timed.
close();
769 if (m_enable_subscribe_ros_tf)
771 m_rosSubscriberPort_tf_timed.
interrupt();
772 m_rosSubscriberPort_tf_timed.
close();
774 if (m_enable_publish_ros_tf)
776 m_rosPublisherPort_tf_static.
interrupt();
777 m_rosPublisherPort_tf_static.
close();
779 if (m_enable_subscribe_ros_tf)
781 m_rosSubscriberPort_tf_static.
interrupt();
782 m_rosSubscriberPort_tf_static.
close();
794 std::lock_guard<std::mutex> lock(m_mutex);
803 repeat_check =
false;
804 size_t tfVecSize_timed_yarp = m_yarp_timed_transform_storage->
size();
805 for (
size_t i = 0; i < tfVecSize_timed_yarp; i++)
807 if (current_time - (*m_yarp_timed_transform_storage)[i].timestamp > m_FrameTransformTimeout)
815 while (repeat_check);
820 repeat_check =
false;
821 size_t tfVecSize_timed_ros = m_ros_timed_transform_storage->
size();
822 for (
size_t i = 0; i < tfVecSize_timed_ros; i++)
824 if (current_time - (*m_ros_timed_transform_storage)[i].timestamp > m_FrameTransformTimeout)
831 }
while (repeat_check);
834 if (m_enable_subscribe_ros_tf)
839 rosInData_timed = m_rosSubscriberPort_tf_timed.
read(
false);
840 if (rosInData_timed !=
nullptr)
842 std::vector <yarp::rosmsg::geometry_msgs::TransformStamped> tfs = rosInData_timed->
transforms;
843 size_t tfs_size = tfs.size();
844 for (
size_t i = 0; i < tfs_size; i++)
847 t.translation.tX = tfs[i].transform.translation.x;
848 t.translation.tY = tfs[i].transform.translation.y;
849 t.translation.tZ = tfs[i].transform.translation.z;
850 t.rotation.x() = tfs[i].transform.rotation.x;
851 t.rotation.y() = tfs[i].transform.rotation.y;
852 t.rotation.z() = tfs[i].transform.rotation.z;
853 t.rotation.w() = tfs[i].transform.rotation.w;
854 t.src_frame_id = tfs[i].header.frame_id;
855 t.dst_frame_id = tfs[i].child_frame_id;
859 (*m_ros_timed_transform_storage).set_transform(
t);
862 }
while (rosInData_timed !=
nullptr);
867 rosInData_static = m_rosSubscriberPort_tf_static.
read(
false);
868 if (rosInData_static !=
nullptr)
870 std::vector <yarp::rosmsg::geometry_msgs::TransformStamped> tfs = rosInData_static->
transforms;
871 size_t tfs_size = tfs.size();
872 for (
size_t i = 0; i < tfs_size; i++)
875 t.translation.tX = tfs[i].transform.translation.x;
876 t.translation.tY = tfs[i].transform.translation.y;
877 t.translation.tZ = tfs[i].transform.translation.z;
878 t.rotation.x() = tfs[i].transform.rotation.x;
879 t.rotation.y() = tfs[i].transform.rotation.y;
880 t.rotation.z() = tfs[i].transform.rotation.z;
881 t.rotation.w() = tfs[i].transform.rotation.w;
882 t.src_frame_id = tfs[i].header.frame_id;
883 t.dst_frame_id = tfs[i].child_frame_id;
887 (*m_ros_static_transform_storage).set_transform(
t);
890 }
while (rosInData_static !=
nullptr);
894 m_lastStateStamp.
update();
895 size_t tfVecSize_static_yarp = m_yarp_static_transform_storage->
size();
896 size_t tfVecSize_timed_yarp = m_yarp_timed_transform_storage->
size();
897 size_t tfVecSize_static_ros = m_ros_static_transform_storage->
size();
898 size_t tfVecSize_timed_ros = m_ros_timed_transform_storage->
size();
900 yCDebug(FRAMETRANSFORMSERVER) <<
"yarp size" << tfVecSize_yarp <<
"ros_size" << tfVecSize_ros;
905 for (
size_t i = 0; i < tfVecSize_static_yarp; i++)
908 transform.
addString((*m_yarp_static_transform_storage)[i].src_frame_id);
909 transform.
addString((*m_yarp_static_transform_storage)[i].dst_frame_id);
910 transform.
addFloat64((*m_yarp_static_transform_storage)[i].timestamp);
912 transform.
addFloat64((*m_yarp_static_transform_storage)[i].translation.tX);
913 transform.
addFloat64((*m_yarp_static_transform_storage)[i].translation.tY);
914 transform.
addFloat64((*m_yarp_static_transform_storage)[i].translation.tZ);
916 transform.
addFloat64((*m_yarp_static_transform_storage)[i].rotation.w());
917 transform.
addFloat64((*m_yarp_static_transform_storage)[i].rotation.x());
918 transform.
addFloat64((*m_yarp_static_transform_storage)[i].rotation.y());
919 transform.
addFloat64((*m_yarp_static_transform_storage)[i].rotation.z());
921 for (
size_t i = 0; i < tfVecSize_timed_yarp; i++)
924 transform.
addString((*m_yarp_timed_transform_storage)[i].src_frame_id);
925 transform.
addString((*m_yarp_timed_transform_storage)[i].dst_frame_id);
926 transform.
addFloat64((*m_yarp_timed_transform_storage)[i].timestamp);
928 transform.
addFloat64((*m_yarp_timed_transform_storage)[i].translation.tX);
929 transform.
addFloat64((*m_yarp_timed_transform_storage)[i].translation.tY);
930 transform.
addFloat64((*m_yarp_timed_transform_storage)[i].translation.tZ);
932 transform.
addFloat64((*m_yarp_timed_transform_storage)[i].rotation.w());
933 transform.
addFloat64((*m_yarp_timed_transform_storage)[i].rotation.x());
934 transform.
addFloat64((*m_yarp_timed_transform_storage)[i].rotation.y());
935 transform.
addFloat64((*m_yarp_timed_transform_storage)[i].rotation.z());
937 for (
size_t i = 0; i < tfVecSize_timed_ros; i++)
940 transform.
addString((*m_ros_timed_transform_storage)[i].src_frame_id);
941 transform.
addString((*m_ros_timed_transform_storage)[i].dst_frame_id);
942 transform.
addFloat64((*m_ros_timed_transform_storage)[i].timestamp);
944 transform.
addFloat64((*m_ros_timed_transform_storage)[i].translation.tX);
945 transform.
addFloat64((*m_ros_timed_transform_storage)[i].translation.tY);
946 transform.
addFloat64((*m_ros_timed_transform_storage)[i].translation.tZ);
948 transform.
addFloat64((*m_ros_timed_transform_storage)[i].rotation.w());
949 transform.
addFloat64((*m_ros_timed_transform_storage)[i].rotation.x());
950 transform.
addFloat64((*m_ros_timed_transform_storage)[i].rotation.y());
951 transform.
addFloat64((*m_ros_timed_transform_storage)[i].rotation.z());
953 for (
size_t i = 0; i < tfVecSize_static_ros; i++)
956 transform.
addString((*m_ros_static_transform_storage)[i].src_frame_id);
957 transform.
addString((*m_ros_static_transform_storage)[i].dst_frame_id);
958 transform.
addFloat64((*m_ros_static_transform_storage)[i].timestamp);
960 transform.
addFloat64((*m_ros_static_transform_storage)[i].translation.tX);
961 transform.
addFloat64((*m_ros_static_transform_storage)[i].translation.tY);
962 transform.
addFloat64((*m_ros_static_transform_storage)[i].translation.tZ);
964 transform.
addFloat64((*m_ros_static_transform_storage)[i].rotation.w());
965 transform.
addFloat64((*m_ros_static_transform_storage)[i].rotation.x());
966 transform.
addFloat64((*m_ros_static_transform_storage)[i].rotation.y());
967 transform.
addFloat64((*m_ros_static_transform_storage)[i].rotation.z());
971 m_streamingPort.
write();
974 if (m_enable_publish_ros_tf)
976 static int rosMsgCounter = 0;
980 for (
size_t i = 0; i < tfVecSize_timed_yarp; i++)
982 transform_timed.
child_frame_id = (*m_yarp_timed_transform_storage)[i].dst_frame_id;
983 transform_timed.
header.
frame_id = (*m_yarp_timed_transform_storage)[i].src_frame_id;
984 transform_timed.
header.
seq = rosMsgCounter;
985 transform_timed.
header.
stamp = (*m_yarp_timed_transform_storage)[i].timestamp;
986 transform_timed.
transform.
rotation.
x = (*m_yarp_timed_transform_storage)[i].rotation.x();
987 transform_timed.
transform.
rotation.
y = (*m_yarp_timed_transform_storage)[i].rotation.y();
988 transform_timed.
transform.
rotation.
z = (*m_yarp_timed_transform_storage)[i].rotation.z();
989 transform_timed.
transform.
rotation.
w = (*m_yarp_timed_transform_storage)[i].rotation.w();
994 rosOutData_timed.
transforms.push_back(transform_timed);
996 m_rosPublisherPort_tf_timed.
write();
1001 for (
size_t i = 0; i < tfVecSize_static_yarp; i++)
1003 transform_static.
child_frame_id = (*m_yarp_static_transform_storage)[i].dst_frame_id;
1004 transform_static.
header.
frame_id = (*m_yarp_static_transform_storage)[i].src_frame_id;
1005 transform_static.
header.
seq = rosMsgCounter;
1007 transform_static.
transform.
rotation.
x = (*m_yarp_static_transform_storage)[i].rotation.x();
1008 transform_static.
transform.
rotation.
y = (*m_yarp_static_transform_storage)[i].rotation.y();
1009 transform_static.
transform.
rotation.
z = (*m_yarp_static_transform_storage)[i].rotation.z();
1010 transform_static.
transform.
rotation.
w = (*m_yarp_static_transform_storage)[i].rotation.w();
1015 rosOutData_static.
transforms.push_back(transform_static);
1017 m_rosPublisherPort_tf_static.
write();
1025 yCError(FRAMETRANSFORMSERVER,
"Returned error");
1031 yCTrace(FRAMETRANSFORMSERVER,
"Close");
1032 if (PeriodicThread::isRunning())
1034 PeriodicThread::stop();