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

Error "Call to publish() on an invalid Publisher" using ApproximateTime Policy

asked 2019-04-18 23:32:05 -0500

RLoad gravatar image

updated 2019-04-19 21:04:17 -0500

Hi everyone, I try to use the ApproximateTime Policy-Based Synchronizer to get the force and position data from a force sensor and NDI, the code is show here which imitated from #q297174, in this code, I try to use geometry_msgs::TransformStamped to get force and position data in one topic and publish it in callback, but it reported a mistake when the code run. then I try to publish the topic of force and position separately. it still fail under same mistake:

[ INFO] [1555644883.009164946]: Synchronization successful [10.000000]
[FATAL] [1555644883.009201476]: ASSERTION FAILED
    file = /opt/ros/indigo/include/ros/publisher.h
    line = 102
    cond = false
    message = 
[FATAL] [1555644883.009213278]: Call to publish() on an invalid Publisher
[FATAL] [1555644883.009220410]: 

Trace/breakpoint trap (core dumped)

[ INFO] [1555646329.618371967]: Synchronization successful [10.000000]
[FATAL] [1555646329.618447480]: ASSERTION FAILED
    file = /opt/ros/indigo/include/ros/publisher.h
    line = 69
    cond = false
    message = 
[FATAL] [1555646329.618476584]: Call to publish() on an invalid Publisher
[FATAL] [1555646329.618495410]: 

Trace/breakpoint trap (core dumped)

and the code is show here:

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

using namespace message_filters;
//tf2_ros::TransformBroadcaster tf2_broadcaster;
geometry_msgs::TransformStamped transformStamped;

//ros::Publisher sensor_pub;
ros::Publisher sensor_pub1;
ros::Publisher sensor_pub2;

void callback(const geometry_msgs::WrenchStampedConstPtr& netft_data_msg, const geometry_msgs::PoseArrayConstPtr& targets);  

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

  ros::NodeHandle nh;

  //ros::Publisher sensor_pub = nh.advertise<geometry_msgs::TransformStamped>("/sensor_together", 1000);
  ros::Publisher sensor_pub1 = nh.advertise<geometry_msgs::WrenchStamped>("/sensor_ati", 1000);
  ros::Publisher sensor_pub2 = nh.advertise<geometry_msgs::PoseArray>("/sensor_ndi", 1000);

  message_filters::Subscriber<geometry_msgs::WrenchStamped> force_sub(nh, "/netft_data", 1);    
  message_filters::Subscriber<geometry_msgs::PoseArray> pose_sub(nh, "/polaris_sensor/targets", 1);    
  //message_filters::TimeSynchronizer<geometry_msgs::WrenchStamped, geometry_msgs::PoseArray> sync(force_sub, pose_sub, 2);       
  typedef sync_policies::ApproximateTime<geometry_msgs::WrenchStamped, geometry_msgs::PoseArray> MySyncPolicy;
  // ApproximateTime takes a queue size as its constructor argument, hence MySyncPolicy(10)
  Synchronizer<MySyncPolicy> sync(MySyncPolicy(10), force_sub, pose_sub);
  sync.registerCallback(boost::bind(&callback, _1, _2));                   

  // sensor_pub.publish(sync);

  ros::spin();

  return 0;
}

void callback(const geometry_msgs::WrenchStampedConstPtr& netft_data_msg, 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_msg->wrench.force.x;
  transformStamped.transform.rotation.y = netft_data_msg->wrench.force.y;
  transformStamped.transform.rotation.z = netft_data_msg->wrench.force.z;
  transformStamped.transform.rotation.w = targets->poses[0].orientation.w;

  //tf2_broadcaster.sendTransform(transformStamped);

  ROS_INFO("Synchronization successful [%f]", 10.00);//transformStamped.transform.rotation.z

  //sensor_pub.publish(transformStamped);
  sensor_pub1.publish(netft_data_msg);
  sensor_pub2.publish(targets);
}

I edit the code and read the data without using the publisher:

#include "ros/ros.h"
#include <sstream>
#include <iostream>
#include ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
4

answered 2019-04-19 01:48:00 -0500

gvdhoorn gravatar image

We see this in your code:

//ros::Publisher sensor_pub;
ros::Publisher sensor_pub1;
ros::Publisher sensor_pub2;

[..]

int main(int argc, char** argv)
{
  [..]

  ros::Publisher sensor_pub1 = nh.advertise<geometry_msgs::WrenchStamped>("/sensor_ati", 1000);
  ros::Publisher sensor_pub2 = nh.advertise<geometry_msgs::PoseArray>("/sensor_ndi", 1000);

  [..]
}

The issue here is that you first declare two variables in the global scope, but then never initialise them.

This is because the two lines in main(..) that advertise(..) the topics assign the result of NodeHandle::advertise<..>(..) to two function scope variables with the same name, causing sensor_pub1 and sensor_pub2 in the global scope to never be initialised.

Your callback(..) in the end tries to call publish(..) on the uninitialised Publisher, leading to the error you show (and which probably makes sense now: Call to publish() on an invalid Publisher).

edit flag offensive delete link more

Comments

Please note that this is a C++ issue. Not a ROS problem.

gvdhoorn gravatar image gvdhoorn  ( 2019-04-19 01:48:22 -0500 )edit

thanks for your help, and I'm not very good at C++, I will learn more about it. now I try to directly read the data in callback and not use publisher, it works and I can get the data after Synchronize.

RLoad gravatar image RLoad  ( 2019-04-19 20:42:37 -0500 )edit

the reason I use publisher is that I want record the data after synchronizing, and now ( I re-edit the code) the use of ROS_INFO let can see the one line data of geometry_msgs::TransformStamped. but now I wonder if there are some better way to record the data in callback? Did ROS provide some good tools for these or I need use some C++ ways to record the data in geometry_msgs::TransformStamped ? Thank you again!

RLoad gravatar image RLoad  ( 2019-04-19 21:00:32 -0500 )edit
1

You should change

ros::Publisher sensor_pub1 = nh.advertise<geometry_msgs::WrenchStamped>("/sensor_ati", 1000);
ros::Publisher sensor_pub2 = nh.advertise<geometry_msgs::PoseArray>("/sensor_ndi", 1000);

to

sensor_pub1 = nh.advertise<geometry_msgs::WrenchStamped>("/sensor_ati", 1000);
sensor_pub2 = nh.advertise<geometry_msgs::PoseArray>("/sensor_ndi", 1000);

so that you use global variable instead of creating new local variable.

ahendrix gravatar image ahendrix  ( 2019-04-19 22:34:58 -0500 )edit

I change my code as your advice, it works! thank you very much!

RLoad gravatar image RLoad  ( 2019-04-22 02:06:15 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2019-04-18 23:32:05 -0500

Seen: 2,405 times

Last updated: Apr 19 '19