ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

using time_synchronizer to combine the force and position data from different sensor

asked 2018-12-27 00:45:30 -0500

RLoad gravatar image

updated 2018-12-27 05:10:35 -0500

jayess gravatar image

Hi everyone, I try to use the time_synchronizer to get the force and position data from a force sensor and NDI, the code is show here which imitated from #q297174:

#include "ros/ros.h"
#include <sstream>
#include <iostream>
#include <fstream>
#include <string>
#include <stdio.h>
#include <message_filters/subscriber.h>
#include <message_filters/time_synchronizer.h>
#include <geometry_msgs/TransformStamped.h>
#include <tf2/LinearMath/Quaternion.h>
#include <tf2_ros/transform_broadcaster.h>
#include <geometry_msgs/Wrench.h>       
#include <geometry_msgs/PoseArray.h>  
#include "std_msgs/Float64.h"

void callback(const geometry_msgs::WrenchConstPtr& netft_data, const geometry_msgs::PoseArrayConstPtr& targets) 
{

  static tf2_ros::TransformBroadcaster tf2_broadcaster;

  geometry_msgs::TransformStamped transformStamped;

  transformStamped.header.stamp = ros::Time::now();
  transformStamped.header.frame_id = "ts_frame";
  transformStamped.child_frame_id = "prism_frame";
  transformStamped.transform.translation.x = targets->poses[0].position.x;
  transformStamped.transform.translation.y = targets->poses[0].position.y;
  transformStamped.transform.translation.z = targets->poses[0].position.z;
  tf2::Quaternion q;
  transformStamped.transform.rotation.x = netft_data->force.x;
  transformStamped.transform.rotation.y = netft_data->force.y;
  transformStamped.transform.rotation.z = netft_data->force.z;

  transformStamped.transform.rotation.w = targets->poses[0].orientation.w;

  tf2_broadcaster.sendTransform(transformStamped);
}

int main(int argc, char** argv)
{
  ros::init(argc, argv, "get_all_sensor_in_one");

  ros::NodeHandle nh;

  message_filters::Subscriber<geometry_msgs::Wrench> force_sub(nh, "/netft_data", 1);   
  message_filters::Subscriber<geometry_msgs::PoseArray> pose_sub(nh, "/targets", 1);     
  message_filters::TimeSynchronizer<geometry_msgs::Wrench, geometry_msgs::PoseArray> sync(force_sub, pose_sub, 10);      
  sync.registerCallback(boost::bind(&callback, _1, _2));       


  ros::spin();

  return 0;
}

what i do is just change the topic and the type of argument, but it is wrong somewhere. I'm pretty new of this, so can you help me??

error:

In file included from /opt/ros/indigo/include/message_filters/time_synchronizer.h:39:0,
                 from /home/edward/kuka_catkin/src/iiwa_stack-master-Sunrise1.9/iiwa_ros/src/topic_synchronizer/get_all_sensor_in_one.cpp:8:
/opt/ros/indigo/include/message_filters/sync_policies/exact_time.h: In instantiation of ‘void message_filters::sync_policies::ExactTime<M0, M1, M2, M3, M4, M5, M6, M7, M8>::add(const typename boost::mpl::at_c<typename message_filters::PolicyBase<M0, M1, M2, M3, M4, M5, M6, M7, M8>::Events, i>::type&) [with int i = 0; M0 = geometry_msgs::Wrench_<std::allocator<void> >; M1 = geometry_msgs::PoseArray_<std::allocator<void> >; M2 = message_filters::NullType; M3 = message_filters::NullType; M4 = message_filters::NullType; M5 = message_filters::NullType; M6 = message_filters::NullType; M7 = message_filters::NullType; M8 = message_filters::NullType; typename boost::mpl::at_c<typename message_filters::PolicyBase<M0, M1, M2, M3, M4, M5, M6, M7, M8>::Events, i>::type = ros::MessageEvent<const geometry_msgs::Wrench_<std::allocator<void> > >]’:
/opt/ros/indigo/include/message_filters/synchronizer.h:358:5:   required from ‘void message_filters::Synchronizer<Policy>::cb(const typename boost::mpl::at_c<typename Policy::Events, i>::type&) [with int i = 0; Policy = message_filters::sync_policies::ExactTime<geometry_msgs::Wrench_<std::allocator<void> >, geometry_msgs::PoseArray_<std::allocator<void> >, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType>; typename boost::mpl::at_c<typename Policy::Events, i>::type = ros::MessageEvent<const geometry_msgs::Wrench_<std::allocator<void> > >]’
/opt/ros/indigo/include/message_filters/synchronizer.h:290:138:   required from ‘void message_filters::Synchronizer<Policy>::connectInput(F0&, F1&, F2&, F3&, F4&, F5&, F6&, F7&, F8&) [with F0 = message_filters::Subscriber<geometry_msgs::Wrench_<std::allocator<void> > >; F1 = message_filters::Subscriber<geometry_msgs ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
1

answered 2018-12-27 04:40:14 -0500

gvdhoorn gravatar image

updated 2018-12-27 04:44:28 -0500

/opt/ros/indigo/include/message_filters/sync_policies/exact_time.h:127:101: error: ‘value’ is not a member of ‘ros::message_traits::TimeStamp<geometry_msgs::Wrench_<std::allocator<void> >, void>’
     Tuple& t = tuples_[mt::TimeStamp<typename mpl::at_c<Messages, i>::type>::value(*evt.getMessage())];

Wrench messaged do not include a Header field (docs). Without a header, there is no timestamp information available with which the TimeSynchronizer can synchronise incoming messages. From the wiki page:

The TimeSynchronizer filter synchronizes incoming channels by the timestamps contained in their headers [..]

You'll need to use a message with a Header, such as geometry_msgs/WrenchStamped.

what i do is just change the topic and the type of argument, but it is wrong somewhere

that is a good approach, but as most things are (almost statically) typed with topics (at least in C++), can lead to issues such as the one you encountered.

edit flag offensive delete link more

Comments

Thanks a lot! It works! While I still have some question just like you mention. Now I put the data of position and force which have same timestamp into one message with type of TransformStamped, while the force is put into the rotation of TransformStamped.

RLoad gravatar image RLoad  ( 2018-12-27 20:22:35 -0500 )edit

Sure this will make some trouble in future, so what should I do to save all this data from sensors (position,orientation,force,torque) to a message or a topic which is convenience to record or used in future? Thanks you!

RLoad gravatar image RLoad  ( 2018-12-27 20:26:40 -0500 )edit

PoseArray already has a Header, so no need to change that. Wrench has a variant with a Header called WrenchStamped.

Don't use TransformStamped, it's not meant for this type of application.

gvdhoorn gravatar image gvdhoorn  ( 2018-12-28 03:16:27 -0500 )edit

Thank you and Happy New Year, I already change the Wrench to the WrenchStamped, it works well. Can you recommend a better way to do this work? I'm not so familiar with this. Thanks again.

RLoad gravatar image RLoad  ( 2019-01-01 02:52:33 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2018-12-27 00:45:30 -0500

Seen: 278 times

Last updated: Dec 27 '18