Coder Social home page Coder Social logo

clydemcqueen / orca3 Goto Github PK

View Code? Open in Web Editor NEW
66.0 7.0 15.0 4.98 MB

ROS2 AUV based on the BlueRobotics BlueROV2 and Navigation2

License: MIT License

CMake 3.95% C++ 75.64% Python 18.56% Shell 0.90% Dockerfile 0.54% OpenSCAD 0.42%
auv gazebo-plugins nav2-plugins bluerov2 ros2

orca3's Introduction

Orca3 example branch parameter

Orca3 is a set of ROS2 packages that provide basic AUV (Autonomous Underwater Vehicle) functionality for the BlueRobotics BlueROV2.

Update 17-June-2022: work has shifted to Orca4, which uses ArduSub as the flight controller.

Orca3 includes a base_controller node that responds to 3D 4DoF /cmd_vel messages and generates thrust and odometry. The BlueROV2 barometer sensor is used to hover at the target depth. See orca_base for details.

Orca3 supports two SLAM (Simultaneous Localization And Mapping) systems:

  • fiducial_vlam looks for ArUco markers in the environment using the forward-facing camera.
  • orb_slam2_ros looks for ORB features along the seafloor. It is currently configured to use a custom down-facing stereo camera, but the underlying ORB-SLAM2 system also works with depth and monocular cameras.
  • Localization details

Orca3 uses the ROS2 Navigation2 framework for mission planning and navigation. Several Nav2 plugins are provided to work in a maritime environment:

  • straight_line_planner_3d
  • pure_pursuit_3d
  • progress_checker_3d
  • goal_checker_3d
  • Nav2 plugin details

Orca3 is simulated in Gazebo 11. Several Gazebo plugins are provided to support a maritime environment:

Orca3 includes experimental hardware drivers that run on a modified BlueROV2:

  • BarometerNode reads the barometer and sends /barometer messages
  • DriverNode responds to /thrust, /lights and /camera_tilt messages
  • Hardware driver details

Installation

Orca3 has been tested on ROS2 Foxy and Galactic. See the Dockerfile for installation instructions.

Simulation with fiducial_vlam

In a terminal run:

cd ~/ros2/orca_ws
source src/orca3/setup.bash
ros2 launch orca_bringup sim_launch.py gzclient:=True rviz:=True slam:=vlam world:=ping_pong

This will start Gazebo, Rviz2 and a bunch of ROS2 nodes. If everything started correctly, you will see Gazebo and Rviz2 GUIs like this:

Gazebo GUI RVIZ2 vlam GUI

The surface of the water is at Z=0 and the AUV will be sitting at the surface. There's one ArUco marker directly in front of the AUV to provide a good initial pose. There are two more AUV markers 2 meters below the surface, facing each other 10 meters apart.

Execute a mission by calling the FollowWaypoints action in a second terminal:

cd ~/ros2/orca_ws
source src/orca3/setup.bash

# Arm sub, turn on hover and vertical pid controller
ros2 topic pub --once /teleop orca_msgs/Teleop "{armed: true, hover_thrust: true, pid_enabled: True}"

# Aligns with markers on the ping-pong map
ros2 action send_goal /follow_waypoints nav2_msgs/action/FollowWaypoints "{poses: [\
{header: {frame_id: 'map'}, pose: {position: {x: 4, z: -2}}},\
{header: {frame_id: 'map'}, pose: {position: {x: -4, z: -2}}},\
{header: {frame_id: 'map'}, pose: {position: {x: 4, z: -2}}},\
{header: {frame_id: 'map'}, pose: {position: {x: -4, z: -2}}},\
]}"

This mission will dive to -2 meters, then ping-pong between the two submerged markers. The AUV will only trust a marker pose if the marker is within 2 meters, so it will run dead-reckoning ~7 meters between the markers. As the AUV approaches a marker and gets a good pose, the dead-reckoning error is added to the map->odom transform.

Mission vlam

Simulation with orb_slam2_ros

In a terminal run:

cd ~/ros2/orca_ws
source src/orca3/setup.bash
ros2 launch orca_bringup sim_launch.py gzclient:=True rviz:=True slam:=orb world:=empty

This Rviz2 configuration is tuned for orb_slam2_ros:

RVIZ2 ORB_SLAM2 GUI

The surface of the water is at Z=0 and the AUV will be sitting at the surface. The world contains a rocky seafloor 4 meters below the surface, indicated by the blue marker in Rviz2. The pointcloud shows the ORB features recognized by orb_slam2_ros.

Execute a mission by calling the FollowWaypoints action in a second terminal:

cd ~/ros2/orca_ws
source src/orca3/setup.bash

# Arm sub, turn on hover and vertical pid controller
ros2 topic pub --once /teleop orca_msgs/Teleop "{armed: true, hover_thrust: true, pid_enabled: True}"

# Run a 6m x 6m box 1.5m above the seafloor, will do a loop closure
ros2 action send_goal /follow_waypoints nav2_msgs/action/FollowWaypoints "{poses: [\
{header: {frame_id: 'map'}, pose: {position: {x: 3, y: 3, z: -2.5}}},\
{header: {frame_id: 'map'}, pose: {position: {x: -3, y: 3, z: -2.5}}},\
{header: {frame_id: 'map'}, pose: {position: {x: -3, y: -3, z: -2.5}}},\
{header: {frame_id: 'map'}, pose: {position: {x: 3, y: -3, z: -2.5}}},\
{header: {frame_id: 'map'}, pose: {position: {x: 3, y: 3, z: -2.5}}},\
]}"

Mission ORB_SLAM2

This mission will dive to -2.5 meters and move in a 6m x 6m square. The AUV has a good view of the seafloor, and orb_slam2_ros runs at the camera frame rate so the map->odom transform is published at 30fps. There is some odometry error which accumulates in the map->odom transform. You should notice a loop closure when the square is completed. The adjustment is very small.

[orb_slam2_ros_stereo-12] Loop detected!
[orb_slam2_ros_stereo-12] Local Mapping STOP
[orb_slam2_ros_stereo-12] Local Mapping RELEASEStarting Global Bundle Adjustment
[orb_slam2_ros_stereo-12] 
[orb_slam2_ros_stereo-12] Global Bundle Adjustment finished
[orb_slam2_ros_stereo-12] Updating map ...
[orb_slam2_ros_stereo-12] Local Mapping STOP
[orb_slam2_ros_stereo-12] Local Mapping RELEASE
[orb_slam2_ros_stereo-12] Map updated!

Packages

orca3's People

Contributors

clydemcqueen 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

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar

orca3's Issues

Loading worlds

When i loas the worlds from fiducial or orbslam examples i get a void world, so there is no bottom, the fiducial has the qr codes

image

colcon build

When runing the docker if i add the colcon build process i get this error when it is installing orbslam2, when i run it a second time it is installed, i am not sure why

--- stderr: orb_slam2_ros
/root/orca_ws/src/orb_slam_2_ros/orb_slam2/src/Tracking.cc: In member function
cv::Mat ORB_SLAM2::Tracking::GrabImageStereo(const cv::Mat&, const cv::Mat&, const double&)’:
/root/orca_ws/src/orb_slam_2_ros/orb_slam2/src/Tracking.cc:180:137: warning: implicitly-declared ‘ORB_SLAM2::Frame& ORB_SLAM2::Frame::operator=(const ORB_SLAM2::Frame&)’ is deprecated [-Wdeprecated-copy]
  180 |     mCurrentFrame = Frame(mImGray,imGrayRight,timestamp,mpORBextractorLeft,mpORBextractorRight,mpORBVocabulary,mK,mDistCoef,mbf,mThDepth);
      |                                                                                                                                         ^
In file included from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/KeyFrame.h:29,
                 from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/MapPoint.h:24,
                 from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/FrameDrawer.h:25,
                 from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/Tracking.h:29,
                 from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/src/Tracking.cc:22:
/root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/Frame.h:49:5: note: because
ORB_SLAM2::Frame’ has user-provided ‘ORB_SLAM2::Frame::Frame(const ORB_SLAM2::Frame&)’
   49 |     Frame(const Frame &frame);
      |     ^~~~~
/root/orca_ws/src/orb_slam_2_ros/orb_slam2/src/Tracking.cc: In member function
cv::Mat ORB_SLAM2::Tracking::GrabImageRGBD(const cv::Mat&, const cv::Mat&, const double&)’:
/root/orca_ws/src/orb_slam_2_ros/orb_slam2/src/Tracking.cc:211:113: warning: implicitly-declared ‘ORB_SLAM2::Frame& ORB_SLAM2::Frame::operator=(const ORB_SLAM2::Frame&)’ is deprecated [-Wdeprecated-copy]
  211 |     mCurrentFrame = Frame(mImGray,imDepth,timestamp,mpORBextractorLeft,mpORBVocabulary,mK,mDistCoef,mbf,mThDepth);
      |                                                                                                                 ^
In file included from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/KeyFrame.h:29,
                 from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/MapPoint.h:24,
                 from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/FrameDrawer.h:25,
                 from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/Tracking.h:29,
                 from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/src/Tracking.cc:22:
/root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/Frame.h:49:5: note: because
ORB_SLAM2::Frame’ has user-provided ‘ORB_SLAM2::Frame::Frame(const ORB_SLAM2::Frame&)’
   49 |     Frame(const Frame &frame);
      |     ^~~~~
/root/orca_ws/src/orb_slam_2_ros/orb_slam2/src/Tracking.cc: In member function
cv::Mat ORB_SLAM2::Tracking::GrabImageMonocular(const cv::Mat&, const double&)’:/root/orca_ws/src/orb_slam_2_ros/orb_slam2/src/Tracking.cc:239:108: warning: implicitly-declared ‘ORB_SLAM2::Frame& ORB_SLAM2::Frame::operator=(const ORB_SLAM2::Frame&)’ is deprecated [-Wdeprecated-copy]
  239 |         mCurrentFrame = Frame(mImGray,timestamp,mpIniORBextractor,mpORBVocabulary,mK,mDistCoef,mbf,mThDepth);
      |                                                                                                            ^
In file included from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/KeyFrame.h:29,
                 from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/MapPoint.h:24,
                 from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/FrameDrawer.h:25,
                 from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/Tracking.h:29,
                 from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/src/Tracking.cc:22:
/root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/Frame.h:49:5: note: because
ORB_SLAM2::Frame’ has user-provided ‘ORB_SLAM2::Frame::Frame(const ORB_SLAM2::Frame&)’
   49 |     Frame(const Frame &frame);
      |     ^~~~~
/root/orca_ws/src/orb_slam_2_ros/orb_slam2/src/Tracking.cc:241:109: warning: implicitly-declared ‘ORB_SLAM2::Frame& ORB_SLAM2::Frame::operator=(const ORB_SLAM2::Frame&)’ is deprecated [-Wdeprecated-copy]
  241 |         mCurrentFrame = Frame(mImGray,timestamp,mpORBextractorLeft,mpORBVocabulary,mK,mDistCoef,mbf,mThDepth);
      |                                                                                                             ^
In file included from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/KeyFrame.h:29,
                 from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/MapPoint.h:24,
                 from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/FrameDrawer.h:25,
                 from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/Tracking.h:29,
                 from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/src/Tracking.cc:22:
/root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/Frame.h:49:5: note: because
ORB_SLAM2::Frame’ has user-provided ‘ORB_SLAM2::Frame::Frame(const ORB_SLAM2::Frame&)’
   49 |     Frame(const Frame &frame);
      |     ^~~~~
/root/orca_ws/src/orb_slam_2_ros/orb_slam2/src/Tracking.cc: In member function
void ORB_SLAM2::Tracking::Track()’:
/root/orca_ws/src/orb_slam_2_ros/orb_slam2/src/Tracking.cc:466:41: warning: implicitly-declared ‘ORB_SLAM2::Frame& ORB_SLAM2::Frame::operator=(const ORB_SLAM2::Frame&)’ is deprecated [-Wdeprecated-copy]
  466 |         mLastFrame = Frame(mCurrentFrame);
      |                                         ^
In file included from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/KeyFrame.h:29,
                 from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/MapPoint.h:24,
                 from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/FrameDrawer.h:25,
                 from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/Tracking.h:29,
                 from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/src/Tracking.cc:22:
/root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/Frame.h:49:5: note: because
ORB_SLAM2::Frame’ has user-provided ‘ORB_SLAM2::Frame::Frame(const ORB_SLAM2::Frame&)’
   49 |     Frame(const Frame &frame);
      |     ^~~~~
/root/orca_ws/src/orb_slam_2_ros/orb_slam2/src/Tracking.cc: In member function
void ORB_SLAM2::Tracking::StereoInitialization()’:
/root/orca_ws/src/orb_slam_2_ros/orb_slam2/src/Tracking.cc:525:41: warning: implicitly-declared ‘ORB_SLAM2::Frame& ORB_SLAM2::Frame::operator=(const ORB_SLAM2::Frame&)’ is deprecated [-Wdeprecated-copy]
  525 |         mLastFrame = Frame(mCurrentFrame);
      |                                         ^
In file included from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/KeyFrame.h:29,
                 from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/MapPoint.h:24,
                 from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/FrameDrawer.h:25,
                 from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/Tracking.h:29,
                 from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/src/Tracking.cc:22:
/root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/Frame.h:49:5: note: because
ORB_SLAM2::Frame’ has user-provided ‘ORB_SLAM2::Frame::Frame(const ORB_SLAM2::Frame&)’
   49 |     Frame(const Frame &frame);
      |     ^~~~~
/root/orca_ws/src/orb_slam_2_ros/orb_slam2/src/Tracking.cc: In member function
void ORB_SLAM2::Tracking::MonocularInitialization()’:
/root/orca_ws/src/orb_slam_2_ros/orb_slam2/src/Tracking.cc:552:48: warning: implicitly-declared ‘ORB_SLAM2::Frame& ORB_SLAM2::Frame::operator=(const ORB_SLAM2::Frame&)’ is deprecated [-Wdeprecated-copy]
  552 |             mInitialFrame = Frame(mCurrentFrame);
      |                                                ^
In file included from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/KeyFrame.h:29,
                 from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/MapPoint.h:24,
                 from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/FrameDrawer.h:25,
                 from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/Tracking.h:29,
                 from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/src/Tracking.cc:22:
/root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/Frame.h:49:5: note: because
ORB_SLAM2::Frame’ has user-provided ‘ORB_SLAM2::Frame::Frame(const ORB_SLAM2::Frame&)’
   49 |     Frame(const Frame &frame);
      |     ^~~~~
/root/orca_ws/src/orb_slam_2_ros/orb_slam2/src/Tracking.cc:553:45: warning: implicitly-declared ‘ORB_SLAM2::Frame& ORB_SLAM2::Frame::operator=(const ORB_SLAM2::Frame&)’ is deprecated [-Wdeprecated-copy]
  553 |             mLastFrame = Frame(mCurrentFrame);
      |                                             ^
In file included from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/KeyFrame.h:29,
                 from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/MapPoint.h:24,
                 from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/FrameDrawer.h:25,
                 from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/Tracking.h:29,
                 from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/src/Tracking.cc:22:
/root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/Frame.h:49:5: note: because
ORB_SLAM2::Frame’ has user-provided ‘ORB_SLAM2::Frame::Frame(const ORB_SLAM2::Frame&)’
   49 |     Frame(const Frame &frame);
      |     ^~~~~
/root/orca_ws/src/orb_slam_2_ros/orb_slam2/src/Tracking.cc: In member function
void ORB_SLAM2::Tracking::CreateInitialMapMonocular()’:
/root/orca_ws/src/orb_slam_2_ros/orb_slam2/src/Tracking.cc:709:37: warning: implicitly-declared ‘ORB_SLAM2::Frame& ORB_SLAM2::Frame::operator=(const ORB_SLAM2::Frame&)’ is deprecated [-Wdeprecated-copy]
  709 |     mLastFrame = Frame(mCurrentFrame);
      |                                     ^
In file included from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/KeyFrame.h:29,
                 from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/MapPoint.h:24,
                 from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/FrameDrawer.h:25,
                 from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/Tracking.h:29,
                 from /root/orca_ws/src/orb_slam_2_ros/orb_slam2/src/Tracking.cc:22:
/root/orca_ws/src/orb_slam_2_ros/orb_slam2/include/Frame.h:49:5: note: because
ORB_SLAM2::Frame’ has user-provided ‘ORB_SLAM2::Frame::Frame(const ORB_SLAM2::Frame&)’
   49 |     Frame(const Frame &frame);
      |     ^~~~~
make[2]: *** No rule to make target '/root/orca_ws/src/orb_slam_2_ros/orb_slam2/Thirdparty/g2o/lib/libg2o.so', needed by '/root/orca_ws/src/orb_slam_2_ros/orb_slam2/lib/liborb_slam2_ros_core.so'.  Stop.
make[2]: *** Waiting for unfinished jobs....
make[1]: *** [CMakeFiles/Makefile2:366: CMakeFiles/orb_slam2_ros_core.dir/all] Error 2
make: *** [Makefile:141: all] Error 2
---
Failed   <<< orb_slam2_ros [1min 9s, exited with code 2]

question

Hello, first of all, I would like to express my gratitude for your selfless sharing. Secondly, I get an error when I build colcon:

Starting >>> orca_base
--- stderr: fiducial_vlam                                               
In file included from /home/hang/orca_ws/src/fiducial_vlam/fiducial_vlam/src/convert_util.cpp:5:
/home/hang/orca_ws/src/fiducial_vlam/fiducial_vlam/include/transform_with_covariance.hpp:6:10: fatal error: tf2/LinearMath/Transform.h: 没有那个文件或目录
    6 | #include "tf2/LinearMath/Transform.h"
      |          ^~~~~~~~~~~~~~~~~~~~~~~~~~~~
compilation terminated.
gmake[2]: *** [CMakeFiles/vmap_node.dir/build.make:76:CMakeFiles/vmap_node.dir/src/convert_util.cpp.o] 错误 1
gmake[1]: *** [CMakeFiles/Makefile2:195:CMakeFiles/vmap_node.dir/all] 错误 2
gmake[1]: *** 正在等待未完成的任务....
In file included from /home/hang/orca_ws/src/fiducial_vlam/fiducial_vlam/src/convert_util.cpp:5:
/home/hang/orca_ws/src/fiducial_vlam/fiducial_vlam/include/transform_with_covariance.hpp:6:10: fatal error: tf2/LinearMath/Transform.h: 没有那个文件或目录
    6 | #include "tf2/LinearMath/Transform.h"
      |          ^~~~~~~~~~~~~~~~~~~~~~~~~~~~
compilation terminated.
gmake[2]: *** [CMakeFiles/vmap_main.dir/build.make:90:CMakeFiles/vmap_main.dir/src/convert_util.cpp.o] 错误 1
gmake[1]: *** [CMakeFiles/Makefile2:221:CMakeFiles/vmap_main.dir/all] 错误 2
In file included from /home/hang/orca_ws/src/fiducial_vlam/fiducial_vlam/src/convert_util.cpp:5:
/home/hang/orca_ws/src/fiducial_vlam/fiducial_vlam/include/transform_with_covariance.hpp:6:10: fatal error: tf2/LinearMath/Transform.h: 没有那个文件或目录
    6 | #include "tf2/LinearMath/Transform.h"
      |          ^~~~~~~~~~~~~~~~~~~~~~~~~~~~
compilation terminated.
gmake[2]: *** [CMakeFiles/vloc_main.dir/build.make:90:CMakeFiles/vloc_main.dir/src/convert_util.cpp.o] 错误 1
gmake[2]: *** 正在等待未完成的任务....
In file included from /home/hang/orca_ws/src/fiducial_vlam/fiducial_vlam/src/convert_util.cpp:5:
/home/hang/orca_ws/src/fiducial_vlam/fiducial_vlam/include/transform_with_covariance.hpp:6:10: fatal error: tf2/LinearMath/Transform.h: 没有那个文件或目录
    6 | #include "tf2/LinearMath/Transform.h"
      |          ^~~~~~~~~~~~~~~~~~~~~~~~~~~~
compilation terminated.
gmake[2]: *** [CMakeFiles/vloc_node.dir/build.make:76:CMakeFiles/vloc_node.dir/src/convert_util.cpp.o] 错误 1
gmake[2]: *** 正在等待未完成的任务....
In file included from /home/hang/orca_ws/src/fiducial_vlam/fiducial_vlam/src/fiducial_math.cpp:5:
/home/hang/orca_ws/src/fiducial_vlam/fiducial_vlam/include/transform_with_covariance.hpp:6:10: fatal error: tf2/LinearMath/Transform.h: 没有那个文件或目录
    6 | #include "tf2/LinearMath/Transform.h"
      |          ^~~~~~~~~~~~~~~~~~~~~~~~~~~~
compilation terminated.
gmake[2]: *** [CMakeFiles/vloc_main.dir/build.make:104:CMakeFiles/vloc_main.dir/src/fiducial_math.cpp.o] 错误 1
gmake[1]: *** [CMakeFiles/Makefile2:169:CMakeFiles/vloc_main.dir/all] 错误 2
In file included from /home/hang/orca_ws/src/fiducial_vlam/fiducial_vlam/src/fiducial_math.cpp:5:
/home/hang/orca_ws/src/fiducial_vlam/fiducial_vlam/include/transform_with_covariance.hpp:6:10: fatal error: tf2/LinearMath/Transform.h: 没有那个文件或目录
    6 | #include "tf2/LinearMath/Transform.h"
      |          ^~~~~~~~~~~~~~~~~~~~~~~~~~~~
compilation terminated.
gmake[2]: *** [CMakeFiles/vloc_node.dir/build.make:90:CMakeFiles/vloc_node.dir/src/fiducial_math.cpp.o] 错误 1
In file included from /home/hang/orca_ws/src/fiducial_vlam/fiducial_vlam/include/map.hpp:7,
                 from /home/hang/orca_ws/src/fiducial_vlam/fiducial_vlam/src/map.cpp:2:
/home/hang/orca_ws/src/fiducial_vlam/fiducial_vlam/include/transform_with_covariance.hpp:6:10: fatal error: tf2/LinearMath/Transform.h: 没有那个文件或目录
    6 | #include "tf2/LinearMath/Transform.h"
      |          ^~~~~~~~~~~~~~~~~~~~~~~~~~~~
compilation terminated.
gmake[2]: *** [CMakeFiles/vloc_node.dir/build.make:104:CMakeFiles/vloc_node.dir/src/map.cpp.o] 错误 1
gmake[1]: *** [CMakeFiles/Makefile2:143:CMakeFiles/vloc_node.dir/all] 错误 2
gmake: *** [Makefile:146:all] 错误 2
---

how can i solve it?Looking forward to your reply!

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.