0
$\begingroup$

Rosanswers logo

I am trying to publish the path produced by my global_planner plugin (named my_global_planner) using a publisher named global_plan_pub.

Unfortunately, I keep getting this error when I try to compile my package (named my_global_planner).

It compiles successfully if I comment out the line global_plan_pub.publish(plan) from the global_planner.cpp file.

I have included my header file (named global_planner.h) and source file (named global_planner.cpp) below.

/opt/ros/melodic/include/ros/message_traits.h: In instantiation of ‘static const char* ros::message_traits::MD5Sum<M>::value(const M&) [with M = std::vector<geometry_msgs::PoseStamped_<std::allocator<void> > >]’:
/opt/ros/melodic/include/ros/message_traits.h:254:102:   required from ‘const char* ros::message_traits::md5sum(const M&) [with M = std::vector<geometry_msgs::PoseStamped_<std::allocator<void> > >]’
/opt/ros/melodic/include/ros/publisher.h:113:7:   required from ‘void ros::Publisher::publish(const M&) const [with M = std::vector<geometry_msgs::PoseStamped_<std::allocator<void> > >]’
/home/skpro19/catkin_ws/src/my_global_planner/src/global_planner.cpp:94:33:   required from here
/opt/ros/melodic/include/ros/message_traits.h:125:14: error: ‘const class std::vector<geometry_msgs::PoseStamped_<std::allocator<void> > >’ has no member named ‘__getMD5Sum’
     return m.__getMD5Sum().c_str();
            ~~^~~~~~~~~~~
/opt/ros/melodic/include/ros/message_traits.h: In instantiation of ‘static const char* ros::message_traits::DataType<M>::value(const M&) [with M = std::vector<geometry_msgs::PoseStamped_<std::allocator<void> > >]’:
/opt/ros/melodic/include/ros/message_traits.h:263:104:   required from ‘const char* ros::message_traits::datatype(const M&) [with M = std::vector<geometry_msgs::PoseStamped_<std::allocator<void> > >]’
/opt/ros/melodic/include/ros/publisher.h:113:7:   required from ‘void ros::Publisher::publish(const M&) const [with M = std::vector<geometry_msgs::PoseStamped_<std::allocator<void> > >]’
/home/skpro19/catkin_ws/src/my_global_planner/src/global_planner.cpp:94:33:   required from here
/opt/ros/melodic/include/ros/message_traits.h:142:14: error: ‘const class std::vector<geometry_msgs::PoseStamped_<std::allocator<void> > >’ has no member named ‘__getDataType’
     return m.__getDataType().c_str();
            ~~^~~~~~~~~~~~~
make[2]: *** [CMakeFiles/global_planner_lib.dir/src/global_planner.cpp.o] Error 1
make[1]: *** [CMakeFiles/global_planner_lib.dir/all] Error 2
make: *** [all] Error 2
cd /home/skpro19/catkin_ws/build/my_global_planner; catkin build --get-env my_global_planner | catkin env -si  /usr/bin/make --jobserver-fds=6,7 -j; cd -

global_planner.h

#include <ros/ros.h>
#include <costmap_2d/costmap_2d_ros.h>
#include <costmap_2d/costmap_2d.h>
#include <nav_core/base_global_planner.h>
#include <geometry_msgs/PoseStamped.h>
#include <angles/angles.h>
#include <base_local_planner/world_model.h>
#include <base_local_planner/costmap_model.h>
#include <map>
#include<nav_msgs/Path.h>


#ifndef GLOBAL_PLANNER_CPP
#define GLOBAL_PLANNER_CPP

namespace global_planner {

    class GlobalPlanner : public nav_core::BaseGlobalPlanner {

        struct Point {
            
            __uint32_t x, y; 

            bool operator==(const Point &p1 ) {    return ((p1.x == this->x) && (p1.y == this->y));  }   
            
            bool operator<(const Point &p1 ) const{    return (p1.x < this->x) ;  }   


        };


       


        struct Cell {

            Point point; 
            __uint32_t cost_till_now;

        };


        struct compare_cost{
            
            bool operator() (Cell &p1, Cell &p2) 
            {

                return p1.cost_till_now < p2.cost_till_now;
            }

        };

        public:

            GlobalPlanner();
            GlobalPlanner(std::string name, costmap_2d::Costmap2DROS* costmap_ros);

            void initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros);

            bool makePlan(const geometry_msgs::PoseStamped& start,
                            const geometry_msgs::PoseStamped& goal,
                            std::vector<geometry_msgs::PoseStamped>& plan
                        );

            bool makePlanOne(const geometry_msgs::PoseStamped& start, const geometry_msgs::PoseStamped& goal,  std::vector<geometry_msgs::PoseStamped>& plan );
            bool makePlanTwo(const geometry_msgs::PoseStamped& start, const geometry_msgs::PoseStamped& goal,  std::vector<geometry_msgs::PoseStamped>& plan );


        private: 


            double heu(const Point &p1, const Point &p2);


            costmap_2d::Costmap2D* costmap_ros_;
            costmap_2d::Costmap2DROS *costmap_ros;
            __uint32_t size_x, size_y;
            ros::Publisher global_plan_pub;
            ros::NodeHandle nh_;
    
    };

};

#endif

global_planner.cpp

#include <pluginlib/class_list_macros.h>
#include <my_global_planner/global_planner.h>
#include <tf/tf.h>
#include <queue>
#include<math.h>

//register this planner as a BaseGlobalPlanner plugin
PLUGINLIB_EXPORT_CLASS(global_planner::GlobalPlanner, nav_core::BaseGlobalPlanner)

using namespace std;

namespace global_planner {

  GlobalPlanner::GlobalPlanner (){

  }

  GlobalPlanner::GlobalPlanner(std::string name, costmap_2d::Costmap2DROS* costmap_ros){
    initialize(name, costmap_ros);

  }


  void GlobalPlanner::initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros){

    nh_ = ros::NodeHandle{"~abcd"};

    costmap_ros  = costmap_ros;
    costmap_ros_ = costmap_ros->getCostmap(); 

    size_x = costmap_ros_->getSizeInCellsX(); 
    size_y = costmap_ros_->getSizeInCellsY();

    cout << "global_frame: " << costmap_ros->getGlobalFrameID() << endl;

    

    global_plan_pub = nh_.advertise<nav_msgs::Path>( "my_global_path", 10000 );

  }


  double GlobalPlanner::heu(const Point &p1, const Point &p2) {
    __uint32_t sum = (p1.x - p2.x) * (p1.x - p2.x) + (p1.y - p2.y) * (p1.y - p2.y);

      return sqrt(sum);

  }

  bool GlobalPlanner::makePlan(const geometry_msgs::PoseStamped& start, const geometry_msgs::PoseStamped& goal,  std::vector<geometry_msgs::PoseStamped>& plan ){

    cout << "Inside the make_plan function!" << endl;

    //bool reached  = false;
    
    __uint32_t mx_i, my_i, mx_f, my_f;

    double wx_i, wy_i, wx_f, wy_f;

    wx_i = start.pose.position.x; 
    wy_i = start.pose.position.y;
    wx_f = goal.pose.position.x;
    wy_f = goal.pose.position.y;

    costmap_ros_->worldToMap(wx_i, wy_i, mx_i, my_i);
    costmap_ros_->worldToMap(wx_f, wy_f, mx_f, my_f);

    cout << endl;
    cout << "Printing start pose and goal pose: " << endl;
    cout << "w_i: (" << wx_i << "," << wy_i << ") m_i: (" << mx_i << "," << my_i <<")" << endl;;
    cout << "w_f: (" << wx_f << "," << wy_f << ") m_f: (" << mx_f << "," << my_f <<")" << endl;;
    cout << endl;

    cout << "Sleeping for 1 second!" << endl;
    ros::Duration(1.0).sleep();
    cout << endl;


    for(int i =0 ;i  < 10; i++){

      geometry_msgs::PoseStamped pt = start;
      
      pt.pose.position.x = start.pose.position.x;
      pt.pose.position.y = start.pose.position.y + i;
      plan.push_back(pt);

    }

    nav_msgs::Path my_path;

    my_path.header = start.header;
    my_path.poses = plan;

    global_plan_pub.publish(plan);

    cout << "Returning true!" << endl;
    cout << "Sleeping for 2 seconds!" << endl;
    ros::Duration(2.0).sleep();

    return true;

  }

  
  
};

Originally posted by skpro19 on ROS Answers with karma: 310 on 2021-06-10

Post score: 0

$\endgroup$

1 Answer 1

0
$\begingroup$

Rosanswers logo

It seems that you are issuing the wrong target. Perhaps it is global_plan_pub.publish(my_path); instead of global_plan_pub.publish(plan);.


Originally posted by miura with karma: 1908 on 2021-06-12

This answer was ACCEPTED on the original site

Post score: 1


Original comments

Comment by skpro19 on 2021-06-12:
@miura Thanks. That solved the problem.

Comment by miura on 2021-06-12:
I'm glad it was resolved.

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.

Not the answer you're looking for? Browse other questions tagged or ask your own question.