Giter Club home page Giter Club logo

turtlebot2_demo's Introduction

This repository contains the code and supporting files to run TurtleBot 2 demos using ROS 2. Due to reliance on existing Linux-only code and dependencies, these demos are intended for use only on Linux (that could change in the future).

The following instructions are for ROS Bouncy, if you are using ROS Ardent please refer to these instructions.

This demo assumes that you have an Orbbec Astra depth camera. Extra work would be required to use the Kinect or Asus Xtion Pro. Without an Astra, you can still do joystick teleop. For instructions on how to setup your turtlebot please see Setup your turtlebot2

Installation

Installation from binaries

First, install ROS2 from binaries following these instructions

Then install the turtlebo2 demo specific packages:

export ROS1_DISTRO=melodic
sudo apt install ros-bouncy-turtlebot2* ros-$ROS1_DISTRO-kobuki-ftdi

Installation from source

This assumes that you have ROS Kinetic installed (or at lease have the ros apt repository in your sources)

First, install ROS2 from source following these instructions

Then get the turtlebo2 demos specific code:

cd <YOUR_ROS2_WORKSPACE>
wget https://raw.githubusercontent.com/ros2/turtlebot2_demo/bouncy/turtlebot2_demo.repos
vcs import src < turtlebot2_demo.repos

Install some dependencies:

export ROS1_DISTRO=melodic # or kinetic if using Ubuntu Xenial
sudo apt-get install --no-install-recommends -y libboost-iostreams-dev libboost-regex-dev libboost-system-dev libboost-thread-dev libceres-dev libgoogle-glog-dev liblua5.2-dev libpcl-dev libprotobuf-dev libsdl1.2-dev libsdl-image1.2-dev libsuitesparse-dev libudev-dev libusb-1.0-0-dev libyaml-cpp-dev protobuf-compiler python-sphinx ros-$ROS1_DISTRO-catkin ros-$ROS1_DISTRO-kobuki-driver ros-$ROS1_DISTRO-kobuki-ftdi

Reason for each dependency:

  • ros-$ROS1_DISTRO-kobuki-driver : our ROS 2 kobuki driver builds on top of this package (and its dependencies)
  • ros-$ROS1_DISTRO-kobuki-ftdi : we use a udev rule from this package
  • ros-$ROS1_DISTRO-common-msgs : to support use of the ros1_bridge, we need the ROS 1 messages available (TODO: document use of the bridge to view depth images and other stuff)

Build the ros2 code

For resource constrained platforms we will split the build into 2 steps to make sure not to overflow the memory

colcon build --symlink-install --packages-skip cartographer cartographer_ros cv_bridge opencv_tests ros1_bridge turtlebot2_amcl turtlebot2_drivers turtlebot2_follower turtlebot2_cartographer turtlebot2_teleop vision_opencv

Now the resource intensive packages and the ones depending on ROS1 packages:

source /opt/ros/$ROS1_DISTRO/setup.bash
colcon build --symlink-install --packages-select cartographer cartographer_ros turtlebot2_amcl turtlebot2_cartographer turtlebot2_drivers turtlebot2_follower turtlebot2_teleop

Go grab a coffee (or a meal if you compile on ARM)

Configure a couple of things

Setup the udev rules

Copy the astra udev rules

If you installed from binaries

If you installed from binary you'll need to download the udev rule by hand:

wget https://raw.githubusercontent.com/ros2/ros_astra_camera/ros2/56-orbbec-usb.rules

If you installed from source

cd ~/ros2_ws/src/ros2/ros_astra_camera

Copy the rules file

sudo cp 56-orbbec-usb.rules /etc/udev/rules.d

Copy the kobuki udev rule

sudo cp `rospack find kobuki_ftdi`/57-kobuki.rules /etc/udev/rules.d

Restart the udev service

sudo service udev reload
sudo service udev restart

Source your workspace

If installed from Debian packages

source /opt/ros/$ROS1_DISTRO/setup.bash
source /opt/ros/bouncy/setup.bash

If installed from source

source /opt/ros/$ROS1_DISTRO/setup.bash
source ~/ros2_ws/install/local_setup.bash

You'll need to do this step for every terminal you use for these demos

Run the demos

Joystick teleop

This is a classic teleoperation demo where the robot can be driven around using a gamepad controller. This demo has been tested with logitech controllers and uses RB as a deadman, the left joystick for driving forward/backward and the right joystick for rotation. Try the launch file:

launch `ros2 pkg prefix turtlebot2_teleop`/share/turtlebot2_teleop/launch/turtlebot_joy.py

Or, run the nodes separately:

ros2 run turtlebot2_drivers kobuki_node
ros2 run joy joy_node

Note: this demo assumes that your controller is in D mode (switch on the back) and that the MODE led is on.

Follower

This demo uses the astra camera to detect blobs in the depthimage and follow them Try the launch file:

launch `ros2 pkg prefix turtlebot2_follower`/share/turtlebot2_follower/launch/turtlebot_follow.py

Or, run the nodes separately.

ros2 run turtlebot2_drivers kobuki_node
ros2 run astra_camera astra_camera_node -- -dw 320 -dh 240 -C -I
ros2 run turtlebot2_follower follower

Cartographer (mapping)

This demo is using Google cartographer to build a map of the environment. The resulting map can be visualized in RViz using the ros1_bridge (more information below).

Run the demo

Try the launch file:

launch `ros2 pkg prefix turtlebot2_cartographer`/share/turtlebot2_cartographer/launch/turtlebot_carto_2d.py

Visualize the results

The created map can be visualized in Rviz on a remote computer by using the dynamic bridge that converts messages between ROS1 and ROS2. This assumes that you have a ROS2 dynamic bridge on your system.

Installing the bridge

From binaries:

Setup your sources as explained on the setup sources section and then run

sudo apt update && sudo apt install ros-bouncy-ros1-bridge
From source:

Build your ROS2 workspace as explained in these instructions.

Run the bridge

Terminal A:

. /opt/ros/$ROS1_DISTRO/setup.bash
roscore

Terminal B:

. /opt/ros/$ROS1_DISTRO/setup.bash
. <YOUR_ROS2_WORKSPACE>
ros2 run ros1_bridge dynamic_bridge

Terminal C:

. /opt/ros/$ROS1_DISTRO/setup.bash
rosrun rviz rviz

Topics you can visualize in Rviz:

  • the map on the topic /map
  • the transforms on the topic /tf
  • the depth images on the topic /depth
  • the laserscans on the topic /scans

Note: ROS Bouncy uses cartographer 0.3.0 that doesn't publish an occupancy grid on the /map topic anymore.

AMCL (localization)

See the AMCL demo README

Discussion

What's happening here compared to the ROS 1 versions of these demos? Well, it's 100% ROS 2, with no bridge or shim. We took 4 different approaches in building the different pieces:

  1. Kobuki driver: we wrote a new, very small rclcpp node that calls into the existing kobuki driver packages, which are organized to be roscpp-independent. In this case, we're building on top of ROS 1 packages, but they don't use roscpp or other parts of the ROS 1 middleware, so we're just using them as supporting libraries.
  2. Astra driver: we forked and ported the existing ROS 1 package (there's no roscpp-independent package separation).
  3. Joystick driver: we wrote a simple rclcpp node from scratch (Linux-only for now).
  4. Follower node: we created a new package into which we copied and then ported the ROS 1 follower nodelet.

As we start migrating more code to ROS 2, we'll discover more about these kinds of techniques and arrive at some best practices that we can recommend for similar projects.

turtlebot2_demo's People

Contributors

bfjelds avatar clalancette avatar codebot avatar dhood avatar dirk-thomas avatar dprotti avatar gaoethan avatar gerkey avatar mikaelarguedas avatar nuclearsandwich avatar rohbotics avatar sloretz avatar stonier avatar vdiluoffo avatar winros avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

turtlebot2_demo's Issues

Split up the "turtlebot2_drivers" package

Right now, it is hosting at least 3 different things:

  • The kobuki driver node
  • The dumb teleop node
  • The launch files

We should probably just get rid of dumb_teleop completely. Beyond that, it would probably make sense to fork the upstream https://github.com/yujinrobot/kobuki.git repository to land the updated kobuki driver in (see #34 ). And then the launch files would make more sense as a top-level "robot" package.

Cannot find joy_node?

After finished the build, I can execute the kobuki_node, but I cannot find the joy_node as described in README.md. where to download it?

Cannot build the demo

I followed the doc to build the demo, but received the below error messsages, any suggestions/comments?

Built target dumb_teleop
In file included from ros2_ws/src/turtlebot2_demo/turtlebot2_drivers/src/kobuki_node.cpp:40:0:
ros2_ws/install/include/tf2_ros/transform_broadcaster.h:72:32: error: ‘tf2_msgs’ was not declared in this scope
rclcpp::publisher::Publisher<tf2_msgs::msg::TFMessage>::SharedPtr publisher_;

Port the kobuki core drivers to ROS2

In order to build the current turtlebot2 drivers, one has to very carefully follow the build instructions: https://github.com/ros2/turtlebot2_demo/blob/master/README.md . In particular, during the initial build, Kinetic can not be sourced, otherwise it causes compilation errors. Then, the user has to source Kinetic and build just the turtlebot2 parts of the stack. Failing to follow this exact sequence can lead to API conflicts in tf2_ros, as seen in #74 . One thing we should do to work around this is to actually port libkobuki.so into ROS2 so that we don't have to have this dance with Kinetic.

console spam if no joystick connected

maybe reconsider the use of the restart exit handler

$ launch ~/ros2_ws/src/turtlebot2_demo/turtlebot2_drivers/launch/turtlebot_joy.py
(joy_node) pid 2737: ['joy_node'] (stderr > stdout, all > console)
[joy_node] ahhhh couldn't open /dev/input/js0
(joy_node) rc 1
(joy_node) pid 2738: ['joy_node'] (stderr > stdout, all > console)
[joy_node] ahhhh couldn't open /dev/input/js0
(joy_node) rc 1
(joy_node) pid 2739: ['joy_node'] (stderr > stdout, all > console)
[joy_node] ahhhh couldn't open /dev/input/js0
(joy_node) rc 1
(joy_node) pid 2740: ['joy_node'] (stderr > stdout, all > console)
[joy_node] ahhhh couldn't open /dev/input/js0
(joy_node) rc 1
(joy_node) pid 2741: ['joy_node'] (stderr > stdout, all > console)
...

About contribute to more demos

I am not sure whether this is the place to ask, however we have a turtlebot autonomous mapping repo under ROS indigo for more than 8 months. I would like to transfer it to ROS2 to add to the demos for turtlebot. Any suggestions? Thanks!

Turtlebot2_cartographer mapping overlay

we run the demo "turtlebot2_cartographer/launch/turtlebot_carto_2d.py" on turtlebot2 by Hokuyo laser(enabled urg_node) , but the mapping meet overlays while turn round the robot.

  • Not sure If community met same issues as below pic?
  • Not see flat_world_imu_node_main.cc(from ROS1) is porting to ROS2, will it be the root cause?

Mapping with Hokuyo UTM-30LX
cartographer_mapping_with_laser

can this demo run on ROS2 dashing?

Bug report

Required Info:

  • Operating System:
  • Installation type:
  • Version or commit hash:
  • DDS implementation:
  • Client library (if applicable):

Steps to reproduce issue


Expected behavior

Actual behavior

Additional information


Feature request

Feature description

Implementation considerations

Create 2 Base Support in ROS2 Turtlebot Demo

Feature request

Support Create 2 iRobot base, other 3d sensors.

Feature description

In ROS Kinetic, one can use the iRobot Create 2 base for a turtlebot_demo by updating .bashrc:
export TURTLEBOT_BASE=create
export TURTLEBOT_STACKS=circles
export TURTLEBOT_3D_SENSOR=asus_xtion_pro (alternatively kinect)

Because this robot is still actively sold and marketed, it would be very helpful to have this same option. It is a very affordable option to try the turtlebot demos and it was easy to do with Kinetic.

ROS1 tf2_ros conflicts and interference with ROS2 tf2_ros of header file transform_broadcaster.h

Bug report

When build the turtlebot2_driver package, its kobuki_node depends on ROS1 kobuki_driver, but after running source /opt/ros/kinetic/setup.bash, the building process is directed to use APIs in ROS1 tf2_ros transform_broadcaster.h, howerver, it should use those same APIs which are defined is ROS2 tf2_ros transform_broadcaster.h and have different arguments from ROS1. the following is the build error:

+++ Building 'turtlebot2_drivers'
==> '. /home/ros/Myspace/rosdev/ros2/release-latest/build/turtlebot2_drivers/cmake__build.sh && /usr/bin/make cmake_check_build_system' in '/home/ros/Myspace/rosdev/ros2/release-latest/build/turtlebot2_drivers'
==> '. /home/ros/Myspace/rosdev/ros2/release-latest/build/turtlebot2_drivers/cmake__build.sh && /usr/bin/make -j4 -l4' in '/home/ros/Myspace/rosdev/ros2/release-latest/build/turtlebot2_drivers'
[ 50%] Built target dumb_teleop
[ 75%] Building CXX object CMakeFiles/kobuki_node.dir/src/kobuki_node.cpp.o
/home/ros/Myspace/rosdev/ros2/release-latest/src/ros2/turtlebot2_demo/turtlebot2_drivers/src/kobuki_node.cpp: In function ‘int main(int, char**)’:
/home/ros/Myspace/rosdev/ros2/release-latest/src/ros2/turtlebot2_demo/turtlebot2_drivers/src/kobuki_node.cpp:89:40: error: no matching function for call to ‘tf2_ros::TransformBroadcaster::TransformBroadcaster(std::shared_ptrrclcpp::Node&)’
tf2_ros::TransformBroadcaster br(node);
^
In file included from /home/ros/Myspace/rosdev/ros2/release-latest/src/ros2/turtlebot2_demo/turtlebot2_drivers/src/kobuki_node.cpp:42:0:
/opt/ros/kinetic/share/sophus/../../include/tf2_ros/transform_broadcaster.h:51:3: note: candidate: tf2_ros::TransformBroadcaster::TransformBroadcaster()
TransformBroadcaster();
^
/opt/ros/kinetic/share/sophus/../../include/tf2_ros/transform_broadcaster.h:51:3: note: candidate expects 0 arguments, 1 provided
/opt/ros/kinetic/share/sophus/../../include/tf2_ros/transform_broadcaster.h:48:7: note: candidate: tf2_ros::TransformBroadcaster::TransformBroadcaster(const tf2_ros::TransformBroadcaster&)
class TransformBroadcaster{

^
/opt/ros/kinetic/share/sophus/../../include/tf2_ros/transform_broadcaster.h:48:7: note: no known conversion for argument 1 from ‘std::shared_ptrrclcpp::Node’ to ‘const tf2_ros::TransformBroadcaster&’
/opt/ros/kinetic/share/sophus/../../include/tf2_ros/transform_broadcaster.h:48:7: note: candidate: tf2_ros::TransformBroadcaster::TransformBroadcaster(tf2_ros::TransformBroadcaster&&)
/opt/ros/kinetic/share/sophus/../../include/tf2_ros/transform_broadcaster.h:48:7: note: no known conversion for argument 1 from ‘std::shared_ptrrclcpp::Node’ to ‘tf2_ros::TransformBroadcaster&&’
/home/ros/Myspace/rosdev/ros2/release-latest/src/ros2/turtlebot2_demo/turtlebot2_drivers/src/kobuki_node.cpp:233:34: error: no matching function for call to ‘tf2_ros::TransformBroadcaster::sendTransform(geometry_msgs::msg::TransformStamped_<std::allocator >&)’
br.sendTransform(*odom_tf_msg);
^
In file included from /home/ros/Myspace/rosdev/ros2/release-latest/src/ros2/turtlebot2_demo/turtlebot2_drivers/src/kobuki_node.cpp:42:0:
/opt/ros/kinetic/share/sophus/../../include/tf2_ros/transform_broadcaster.h:63:8: note: candidate: void tf2_ros::TransformBroadcaster::sendTransform(const TransformStamped&)
void sendTransform(const geometry_msgs::TransformStamped & transform);
^
/opt/ros/kinetic/share/sophus/../../include/tf2_ros/transform_broadcaster.h:63:8: note: no known conversion for argument 1 from ‘geometry_msgs::msg::TransformStamped_<std::allocator >’ to ‘const TransformStamped& {aka const geometry_msgs::TransformStamped_<std::allocator >&}’
/opt/ros/kinetic/share/sophus/../../include/tf2_ros/transform_broadcaster.h:67:8: note: candidate: void tf2_ros::TransformBroadcaster::sendTransform(const std::vector<geometry_msgs::TransformStamped_<std::allocator > >&)
void sendTransform(const std::vector<geometry_msgs::TransformStamped> & transforms);
^
/opt/ros/kinetic/share/sophus/../../include/tf2_ros/transform_broadcaster.h:67:8: note: no known conversion for argument 1 from ‘geometry_msgs::msg::TransformStamped_<std::allocator >’ to ‘const std::vector<geometry_msgs::TransformStamped_<std::allocator > >&’
/home/ros/Myspace/rosdev/ros2/release-latest/src/ros2/turtlebot2_demo/turtlebot2_drivers/src/kobuki_node.cpp:250:33: error: no matching function for call to ‘tf2_ros::TransformBroadcaster::sendTransform(geometry_msgs::msg::TransformStamped_<std::allocator >&)’
br.sendTransform(*imu_tf_msg);
^
In file included from /home/ros/Myspace/rosdev/ros2/release-latest/src/ros2/turtlebot2_demo/turtlebot2_drivers/src/kobuki_node.cpp:42:0:
/opt/ros/kinetic/share/sophus/../../include/tf2_ros/transform_broadcaster.h:63:8: note: candidate: void tf2_ros::TransformBroadcaster::sendTransform(const TransformStamped&)
void sendTransform(const geometry_msgs::TransformStamped & transform);
^
/opt/ros/kinetic/share/sophus/../../include/tf2_ros/transform_broadcaster.h:63:8: note: no known conversion for argument 1 from ‘geometry_msgs::msg::TransformStamped_<std::allocator >’ to ‘const TransformStamped& {aka const geometry_msgs::TransformStamped_<std::allocator >&}’
/opt/ros/kinetic/share/sophus/../../include/tf2_ros/transform_broadcaster.h:67:8: note: candidate: void tf2_ros::TransformBroadcaster::sendTransform(const std::vector<geometry_msgs::TransformStamped_<std::allocator > >&)
void sendTransform(const std::vector<geometry_msgs::TransformStamped> & transforms);
^
/opt/ros/kinetic/share/sophus/../../include/tf2_ros/transform_broadcaster.h:67:8: note: no known conversion for argument 1 from ‘geometry_msgs::msg::TransformStamped_<std::allocator >’ to ‘const std::vector<geometry_msgs::TransformStamped_<std::allocator > >&’
CMakeFiles/kobuki_node.dir/build.make:62: recipe for target 'CMakeFiles/kobuki_node.dir/src/kobuki_node.cpp.o' failed
make[2]: *** [CMakeFiles/kobuki_node.dir/src/kobuki_node.cpp.o] Error 1
CMakeFiles/Makefile2:99: recipe for target 'CMakeFiles/kobuki_node.dir/all' failed
make[1]: *** [CMakeFiles/kobuki_node.dir/all] Error 2
Makefile:138: recipe for target 'all' failed
make: *** [all] Error 2

<== Command '. /home/ros/Myspace/rosdev/ros2/release-latest/build/turtlebot2_drivers/cmake__build.sh && /usr/bin/make -j4 -l4' failed in '/home/ros/Myspace/rosdev/ros2/release-latest/build/turtlebot2_drivers' with exit code '2'
<== Command '. /home/ros/Myspace/rosdev/ros2/release-latest/build/turtlebot2_drivers/cmake__build.sh && /usr/bin/make -j4 -l4' failed in '/home/ros/Myspace/rosdev/ros2/release-latest/build/turtlebot2_drivers' with exit code '2'

Required Info:

  • Operating System:
    • Ubuntu 16.04
  • Installation type:
    • ROS2 source and ROS1 Binary
  • Version or commit hash:
    • master
  • DDS implementation:
    • N/A
  • Client library (if applicable):
    • N/A

Steps to reproduce issue

1. Clone the ROS2 release-latest (a.k.a ardent) and turtlebot2_demo ardent branch
2. Run `src/ament/ament_tools/scripts/ament.py build --build-tests --symlink-install --only-packages turtlebot2_drivers` after sourcing the ROS1 setup.bash which is installed in the way of binary package

Expected behavior

No build error and use ROS2 tf2_ros

Actual behavior

use ROS1 tf2_ros

Additional information


Failed to install turtlebot drivers

Bug report

Required Info:

  • Operating System:
    Ubuntu 18.04
  • Installation type:
    Source
  • Version or commit hash:
  • DDS implementation:
  • Client library (if applicable):

turtlebot_drivers

Steps to reproduce issue


Expected behavior

Actual behavior

Failed <<< turtlebot2_drivers [30.0s, exited with code -11]

Additional information

I am trying to install turtlebot2 drivers following the instructions in the repository.
I cannot successfully install the turtlebot2 drivers and therefore I cannot successfully use the demo.

I have reached to a point where I have successfully installed ros2-bouncy from source. Installed ros-melodic. But when I try to build the ros1 libraries it throws an error.
Specifically. I run
colcon build --symlink-install --packages-select cartographer cartographer_ros turtlebot2_amcl turtlebot2_cartographer turtlebot2_drivers turtlebot2_follower turtlebot2_teleop

and I get

Starting >>> turtlebot2_drivers
Starting >>> cartographer                        
Failed   <<< turtlebot2_drivers [30.0s, exited with code -11]                                         
Aborted  <<< cartographer [8min 15s]                                          
                                      
Summary: 0 packages finished [8min 17s]
  1 package failed: turtlebot2_drivers
  1 package aborted: cartographer
  1 package had stderr output: cartographer
  5 packages not processed

Any help in this regard will be deeply appreciated. I am new to ros2, so sorry for noob questions.


Feature request

Feature description

Implementation considerations

Make the kobuki_node more like the ROS1 kobuki node

The ROS1 kobuki node is written as an event-based loop that takes data as it comes in from the serial line and publishes it to ROS directly. In contrast, the current ROS2 kobuki_node polls for data at 20Hz and publishes it.

Because of this, the ROS1 node publishes data at a much higher rate for IMU (100 Hz) and odometry (50Hz).

I started some work on doing this on this branch. It works as intended, but tends to crash. So we should probably figure out why that is and switch to using that for the kobuki node.

Error occur for cartographer_ros

When I install packages use command

src/ament/ament_tools/scripts/ament.py build --isolated --symlink-install --parallel --only cartographer cartographer_ros ceres_solver turtlebot2_amcl turtlebot2_cartographer turtlebot2_drivers turtlebot2_follower turtlebot2_teleop --make-flags -j2 -l2

I get this error like below:

Determining if the pthread_create exist failed with the following output:
Change Dir: /home/wangyawei/RosWorkspace/ros2_ws/build_isolated/cartographer_ros/CMakeFiles/CMakeTmp

Run Build Command:"/usr/bin/make" "cmTC_2f9df/fast"
/usr/bin/make -f CMakeFiles/cmTC_2f9df.dir/build.make CMakeFiles/cmTC_2f9df.dir/build
make[1]: Entering directory '/home/wangyawei/RosWorkspace/ros2_ws/build_isolated/cartographer_ros/CMakeFiles/CMakeTmp'
Building C object CMakeFiles/cmTC_2f9df.dir/CheckSymbolExists.c.o
/usr/bin/cc     -o CMakeFiles/cmTC_2f9df.dir/CheckSymbolExists.c.o   -c /home/wangyawei/RosWorkspace/ros2_ws/build_isolated/cartographer_ros/CMakeFiles/CMakeTmp/CheckSymbolExists.c
Linking C executable cmTC_2f9df
/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTC_2f9df.dir/link.txt --verbose=1
/usr/bin/cc       CMakeFiles/cmTC_2f9df.dir/CheckSymbolExists.c.o  -o cmTC_2f9df 
CMakeFiles/cmTC_2f9df.dir/CheckSymbolExists.c.o: In function `main':
CheckSymbolExists.c:(.text+0x16): undefined reference to `pthread_create'
collect2: error: ld returned 1 exit status
CMakeFiles/cmTC_2f9df.dir/build.make:97: recipe for target 'cmTC_2f9df' failed
make[1]: *** [cmTC_2f9df] Error 1
make[1]: Leaving directory '/home/wangyawei/RosWorkspace/ros2_ws/build_isolated/cartographer_ros/CMakeFiles/CMakeTmp'
Makefile:126: recipe for target 'cmTC_2f9df/fast' failed
make: *** [cmTC_2f9df/fast] Error 2

File /home/wangyawei/RosWorkspace/ros2_ws/build_isolated/cartographer_ros/CMakeFiles/CMakeTmp/CheckSymbolExists.c:
/* */
#include <pthread.h>

int main(int argc, char** argv)
{
  (void)argv;
#ifndef pthread_create
  return ((int*)(&pthread_create))[argc];
#else
  (void)argc;
  return 0;
#endif
}

Determining if the function pthread_create exists in the pthreads failed with the following output:
Change Dir: /home/wangyawei/RosWorkspace/ros2_ws/build_isolated/cartographer_ros/CMakeFiles/CMakeTmp

Run Build Command:"/usr/bin/make" "cmTC_611b6/fast"
/usr/bin/make -f CMakeFiles/cmTC_611b6.dir/build.make CMakeFiles/cmTC_611b6.dir/build
make[1]: Entering directory '/home/wangyawei/RosWorkspace/ros2_ws/build_isolated/cartographer_ros/CMakeFiles/CMakeTmp'
Building C object CMakeFiles/cmTC_611b6.dir/CheckFunctionExists.c.o
/usr/bin/cc    -DCHECK_FUNCTION_EXISTS=pthread_create   -o CMakeFiles/cmTC_611b6.dir/CheckFunctionExists.c.o   -c /usr/share/cmake-3.5/Modules/CheckFunctionExists.c
Linking C executable cmTC_611b6
/usr/bin/cmake -E cmake_link_script CMakeFiles/cmTC_611b6.dir/link.txt --verbose=1
/usr/bin/cc   -DCHECK_FUNCTION_EXISTS=pthread_create    CMakeFiles/cmTC_611b6.dir/CheckFunctionExists.c.o  -o cmTC_611b6 -lpthreads 
/usr/bin/ld: cannot find -lpthreads
collect2: error: ld returned 1 exit status
CMakeFiles/cmTC_611b6.dir/build.make:97: recipe for target 'cmTC_611b6' failed
make[1]: *** [cmTC_611b6] Error 1
make[1]: Leaving directory '/home/wangyawei/RosWorkspace/ros2_ws/build_isolated/cartographer_ros/CMakeFiles/CMakeTmp'
Makefile:126: recipe for target 'cmTC_611b6/fast' failed
make: *** [cmTC_611b6/fast] Error 2

Someone can help me?

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.