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

Call to publish() on an invalid Publisher

asked 2019-03-27 19:25:25 -0500

houssemDZ-25 gravatar image

updated 2022-04-17 11:15:34 -0500

lucasw gravatar image

Hello I have this problem running a simple publisher I'm using ros-kinetic: I've tried to use only one pubilsher instead of 3 a times but it didn't work.

 [FATAL] [1553731918.366515702]: ASSERTION FAILED
        file = /opt/ros/kinetic/include/ros/publisher.h
        line = 102
        cond = false
        message = 

[FATAL] [1553731918.366562090]: Call to publish() on an invalid Publisher
[FATAL] [1553731918.366585837]:

this is my Controller.h

#ifndef CONTROLLER_H
#define CONTROLLER_H
#include <string>
#include <ros/ros.h>
#include <std_msgs/Empty.h>
#include <geometry_msgs/Twist.h>
#include <iostream>    
namespace ardrone_controller{
class Controller
{
    private:
    ros::NodeHandle n_;
    std::string control_topic_name_;
    std::string takeof_topic_name_;
    std::string land_topic_name_;
    ros::Publisher controller_topic_;
    ros::Publisher takeoff_topic_;
    ros::Publisher land_topic_;
    geometry_msgs::Twist desired_position_;
public:
    Controller();
    Controller(std::string control_topic_name, std::string takeof_topic_name,
               std::string land_topic_name);
    void takingOf();
    void landing();
    void controlLaw();
};
} /* for namespace */

#endif

And here is my Controller.cpp

#include <ardrone_controller/controller.hpp>
namespace ardrone_controller{

Controller::Controller()
{
    /* topics name */
    std::string control_topic_name_ ="/cmd_vel";
    std::string takeof_topic_name_  ="/ardrone/takeoff";
    std::string land_topic_name_    = "/ardrone/land";
    /* Initalisation of publishers */
    ros::Publisher controller_topic_ = n_.advertise<geometry_msgs::Twist>(control_topic_name_,10);
    ros::Publisher takeoff_topic_    = n_.advertise<std_msgs::Empty>("/ardrone/takeoff",10);
    ros::Publisher land_topic_       = n_.advertise<std_msgs::Empty>(land_topic_name_,10);
}
Controller::Controller(std::string control_topic_name, std::string takeof_topic_name
                       , std::string land_topic_name)
{
    /* topics name */
    std::string control_topic_name_ = control_topic_name;
    std::string takeof_topic_name_  = takeof_topic_name ;
    std::string land_topic_name_    = land_topic_name   ;
    /* Initalisation of publishers */
    ros::Publisher controller_topic_ = n_.advertise<geometry_msgs::Twist>(control_topic_name_,10);
    ros::Publisher takeoff_topic_    = n_.advertise<std_msgs::Empty>(takeof_topic_name_,10);
    ros::Publisher land_topic_       = n_.advertise<std_msgs::Empty>(land_topic_name_,10);
}

void Controller::takingOf()
{
   ROS_INFO("takingOf");
   std_msgs::Empty msg;
   takeoff_topic_.publish(msg);
}
void Controller::landing()
{
    ROS_INFO("Landing");
    std_msgs::Empty msg;
   takeoff_topic_.publish(msg);
}
void Controller::controlLaw()
{/* just a testing the topic */
    ROS_INFO("control_law");
    std::string dir;
    std::cout << "entre direction \n";
    std::cin >> dir;
    if(dir == "left")
    {
        desired_position_.linear.x = 1;
    }
    else if (dir == "right") {
        desired_position_.linear.y = 1;
    }
    else {
        desired_position_.linear.z = 1;
    }
    controller_topic_.publish(desired_position_);
}

} /* for namespace */

and here is my main :

#include <ardrone_controller/controller.hpp>

int main(int argc, char *argv[])
{
    ros::init(argc , argv ,"controller_node");
    ardrone_controller::Controller control;
    ros::Rate rate(1);

    control.takingOf();
    int k = 0;
    while(ros::ok() && k <10)
    {
        control.controlLaw();
        k++;
        control.takingOf();
        ros::spinOnce();
        rate.sleep();
    }
    control.landing();
    ros::spinOnce();
    return 0;
}
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2019-03-27 19:47:35 -0500

janindu gravatar image

updated 2019-03-27 19:49:41 -0500

It's a C++ error. In your Controller.h header, you declare controller_topic_. However, in your constructor in Controller.cpp, you declare and instantiate controller_topic_ again within the constructor scope. Anywhere outside the constructor can't see it.

It should work once you replace

Controller::Controller()
{
    /* topics name */
    std::string control_topic_name_ ="/cmd_vel";
    std::string takeof_topic_name_  ="/ardrone/takeoff";
    std::string land_topic_name_    = "/ardrone/land";
    /* Initalisation of publishers */
    ros::Publisher controller_topic_ = n_.advertise<geometry_msgs::Twist>(control_topic_name_,10);
    ros::Publisher takeoff_topic_    = n_.advertise<std_msgs::Empty>("/ardrone/takeoff",10);
    ros::Publisher land_topic_       = n_.advertise<std_msgs::Empty>(land_topic_name_,10);
}

with

Controller::Controller()
    {
        /* topics name */
        this->control_topic_name_ ="/cmd_vel";
        this->takeof_topic_name_  ="/ardrone/takeoff";
        this->land_topic_name_    = "/ardrone/land";
        /* Initalisation of publishers */
        this->controller_topic_ = n_.advertise<geometry_msgs::Twist>(control_topic_name_,10);
        this->takeoff_topic_    = n_.advertise<std_msgs::Empty>("/ardrone/takeoff",10);
        this->land_topic_       = n_.advertise<std_msgs::Empty>(land_topic_name_,10);
    }

Note - Do the same for the other constructor as well.

edit flag offensive delete link more

Comments

thank you very much I didn't pay attention that I repeat the declaration now it works

houssemDZ-25 gravatar image houssemDZ-25  ( 2019-03-27 20:07:23 -0500 )edit

No worries. Since this solved the problem, can you please accept the answer so that it goes out of the unanswered queue?

janindu gravatar image janindu  ( 2019-03-27 20:10:22 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2019-03-27 19:25:25 -0500

Seen: 850 times

Last updated: Mar 27 '19