unable to build the package using catkin build
I have a main.cpp
file inside the src
folder of my_explore_lite
package. This is the code inside my main
function (inside the main.cpp
) file -
int main(int argc, char** argv) {
ros::init(argc, argv, "explore_node");
ros::NodeHandle nh("explore_node");
tf2_ros::Buffer buffer(ros::Duration(10));
tf2_ros::TransformListener tf(buffer);
string global_frame, robot_base_frame;
nh.param("global_costmap/global_frame", global_frame, std::string("odom"));
nh.param("global_costmap/robot_base_frame", robot_base_frame, std::string("base_link"));
costmap_2d::Costmap2DROS *global_costmap = new costmap_2d::Costmap2DROS("global_costmap", buffer);
costmap_2d::Costmap2DROS *local_costmap = new costmap_2d::Costmap2DROS("local_costmap", buffer);
cout << "global_frame: " << global_frame << endl;
cout << "robot_base_frame: " << robot_base_frame << endl;
costmap_2d::Costmap2D* global_costmap_ = global_costmap->getCostmap();
unsigned char* global_og = global_costmap_->getCharMap();
//unsigned char* global_og = global_costmap->getCostmap()->getCharMap();
size_t size_x = global_costmap_->getSizeInCellsX();
size_t size_y = global_costmap_->getSizeInCellsY();
cout << "size_x: " << size_x << " size_y: " << size_y << endl;
size_t idx = global_costmap_->getIndex(10, 10);
cout << "idx: " << idx << endl;
cout <<"global_og[idx]: " << (int)global_og[idx] << endl;
//manipulate_center_og(global_costmap_);
geometry_msgs::PoseStamped global_pose;
bool pos = global_costmap->getRobotPose(global_pose);
//cout << "global_pose: " << global_pose << endl;
//detect_initial_frontiers(global_costmap);
explore_level_one(global_costmap);
//ros::spin();
//explore_level_one(global_costmap);
move_base::MoveBase move_base(buffer);
}
This is my CMakelist.txt
:
cmake_minimum_required(VERSION 3.0.2)
project(my_explore_lite)
## Compile as C++11, supported in ROS Kinetic and newer
add_compile_options(-std=c++11)
find_package(catkin REQUIRED COMPONENTS
geometry_msgs
roscpp
std_msgs
nav_msgs
move_base_msgs
actionlib
costmap_2d
move_base
)
## System dependencies are found with CMake's conventions
find_package(Boost REQUIRED COMPONENTS system)
catkin_package(
CATKIN_DEPENDS
nav_msgs
roscpp
std_msgs
message_runtime
move_base_msgs
move_base
)
include_directories(
include
${catkin_INCLUDE_DIRS}
${Boost_INCLUDE_DIRS}
)
add_executable(explore_node src/main.cpp)
target_link_libraries(
explore_node
${catkin_LIBRARIES}
${Boost_LIBRARIES}
)
When I run catkin build my_explore_lite
inside my ~/catkin_ws
folder, I am getting the following error -
Errors << my_explore_lite:make /home/skpro19/catkin_ws/logs/my_explore_lite/build.make.063.log
CMakeFiles/explore_node.dir/src/main.cpp.o: In function `main':
main.cpp:(.text+0x28b1): undefined reference to `move_base::MoveBase::MoveBase(tf2_ros::Buffer&)'
main.cpp:(.text+0x28c0): undefined reference to `move_base::MoveBase::~MoveBase()'
collect2: error: ld returned 1 exit status
make[2]: *** [/home/skpro19/catkin_ws/devel/.private/my_explore_lite/lib/my_explore_lite/explore_node] Error 1
make[1]: *** [CMakeFiles/explore_node.dir/all] Error 2
make: *** [all] Error 2
Asked by skpro19 on 2021-05-08 03:11:42 UTC
Answers
Hi, the problem is it not with your CMakeLists; it's from the navigation package! If you look at catkin_package
(here) in the navigation/move_base
package, it doesn't create any libraries for your to link to your main.cpp
.
Until they update the package, the following fix might work for you,
- Download and compile the navigation package in your catkin workspace, but with either one of the following changes,
- Update my_explore_lite CMakeLists.txt as,
`
target_link_libraries( explore_node move_base ${catkin_LIBRARIES} ${Boost_LIBRARIES})
or - Update move_base CMakeLists.txt as,
catkin_package(
INCLUDE_DIRS include ${EIGEN3_INCLUDE_DIRS}
LIBRARIES move_base
CATKIN_DEPENDS
dynamic_reconfigure
geometry_msgs
move_base_msgs
nav_msgs
roscpp
)
Asked by praskot on 2021-05-12 02:35:40 UTC
Comments
I stumbled upon this question on ROS amswers. Somewhere it says this —
I have downloaded the move_base git, and compiled the base_local_planner agent (which requires to gitclone cmake_modules from github as well, by the way).
Has this got something to do with the problem at hand?
Asked by skpro19 on 2021-05-12 07:51:43 UTC
Not sure, sorry.
Asked by praskot on 2021-05-13 02:24:51 UTC
Comments
This is a C++ error, not really a ros issue. Have you included the move_base header file and linked it to the executable?
Asked by praskot on 2021-05-08 05:23:50 UTC
I have included the following headers in the
main.cpp
file -This is my CMakelist.txt.
Asked by skpro19 on 2021-05-08 05:35:36 UTC
@skpro19: please do not link to external sites for something as central to your problem as your
CMakeLists.txt
.I've included it into your post.
Please remove all the boilerplate comments, such that only the uncommented sections / directives remain.
Asked by gvdhoorn on 2021-05-08 06:12:07 UTC
@gvdhoorn okay.
Asked by skpro19 on 2021-05-10 04:48:35 UTC
@praskot how do I link it to the executable?
Asked by skpro19 on 2021-05-11 01:19:26 UTC