Coder Social home page Coder Social logo

mit-acl / faster Goto Github PK

View Code? Open in Web Editor NEW
913.0 25.0 179.0 109.44 MB

3D Trajectory Planner in Unknown Environments

License: BSD 3-Clause "New" or "Revised" License

CMake 4.88% C++ 89.91% Python 5.21%
uav autonomous-navigation path-planning trajectory-optimization ground-robot planning drone

faster's Introduction

FASTER: Fast and Safe Trajectory Planner for Navigation in Unknown Environments

Accepted for publication in the IEEE Transactions on Robotics (T-RO)

Finalist to the Best Paper Award on Safety, Security, and Rescue Robotics (IROS 2019)

UAV Ground Robot
IROS 2019: FASTER: Fast and Safe Trajectory Planner for Flights in Unknown Environments IROS 2019: FASTER: Fast and Safe Trajectory Planner for Flights in Unknown Environments
IROS 2019: FASTER: Fast and Safe Trajectory Planner for Flights in Unknown Environments IROS 2019: FASTER: Fast and Safe Trajectory Planner for Flights in Unknown Environments

Citation

When using FASTER, please cite the following journal paper (pdf, video)

@article{tordesillas2021faster,
  title={{FASTER}: Fast and Safe Trajectory Planner for Navigation in Unknown Environments},
  author={Tordesillas, Jesus and How, Jonathan P},
  journal={IEEE Transactions on Robotics},
  year={2021},
  publisher={IEEE}
}

The conference version is here:

@inproceedings{tordesillas2019faster,
  title={{FASTER}: Fast and Safe Trajectory Planner for Flights in Unknown Environments},
  author={Tordesillas, Jesus and Lopez, Brett T and How, Jonathan P},
  booktitle={2019 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS)},
  year={2019},
  organization={IEEE}
}

General Setup

FASTER has been tested with

  • Ubuntu 16.04/ROS Kinetic
  • Ubuntu 18.04/ROS Melodic

Other ROS versions may require some minor changes, feel free to create an issue if you have any problems. The Gurobi versions tested are Gurobi 8.1, Gurobi 9.0, and Gurobi 9.1.

Install the Gurobi Optimizer. You can test your installation typing gurobi.sh in the terminal. Have a look at this section if you have any issues.

Install the following dependencies:

sudo apt-get install ros-"${ROS_DISTRO}"-gazebo-ros-pkgs ros-"${ROS_DISTRO}"-mavros-msgs ros-"${ROS_DISTRO}"-tf2-sensor-msgs
python -m pip install pyquaternion

Create a workspace, and clone this repo and its dependencies:

mkdir ws && cd ws && mkdir src && cd src
git clone https://github.com/mit-acl/faster.git
wstool init
wstool merge ./faster/faster/install/faster.rosinstall

In the following, remember (once the workspace is compiled) to add this to your ~/.bashrc:

source PATH_TO_YOUR_WS/devel/setup.bash

Instructions to use FASTER with an aerial robot:

Compile the code:

wstool update -j8
cd ..
catkin config -DCMAKE_BUILD_TYPE=Release
catkin build

And finally open 5 terminals and execute these commands:

roslaunch acl_sim start_world.launch
roslaunch acl_sim perfect_tracker_and_sim.launch
roslaunch global_mapper_ros global_mapper_node.launch
roslaunch faster faster_interface.launch
roslaunch faster faster.launch

The blue grid shown in Rviz is the unknown space and the orange one is the occupied-known space. Now you can click Start in the GUI, and then, in RVIZ, press G (or click the option 2D Nav Goal on the top bar of RVIZ) and click any goal for the drone.

NOTE (TODO): Right now the radius of the drone plotted in Gazebo (which comes from the scale field of quadrotor_base_urdf.xacro) does not correspond with the radius specified in faster.yaml.

Instructions to use FASTER with a ground robot:

IMPORTANT NOTE: There are some important differences on the performance of the ground robot when using the Gazebo version that comes with ROS Kinetic and the one that comes with ROS Melodic. To achieve a good tracking error (like the one shown here), you may have to tune the gains of the controller depending on the specific verion of ROS/Gazebo that you are using.

Install the following dependencies:

sudo apt-get install ros-"${ROS_DISTRO}"-control-toolbox ros-"${ROS_DISTRO}"-ros-control ros-"${ROS_DISTRO}"-robot-localization ros-"${ROS_DISTRO}"-lms1xx ros-"${ROS_DISTRO}"-interactive-marker-twist-server ros-"${ROS_DISTRO}"-hector-gazebo-plugins ros-"${ROS_DISTRO}"-move-base ros-"${ROS_DISTRO}"-ros-control ros-"${ROS_DISTRO}"-ros-controllers ros-"${ROS_DISTRO}"-pointgrey-camera-description ros-"${ROS_DISTRO}"-hardware-interface ros-"${ROS_DISTRO}"-message-to-tf ros-"${ROS_DISTRO}"-gazebo-ros-control

Then download the ground_robot-specific packages and compile the repo:

wstool merge ./faster/faster/install/faster_ground_robot.rosinstall
wstool update -j8
cd ..
catkin config -DCMAKE_BUILD_TYPE=Release
catkin build

Then, in faster.yaml, change these parameters:

drone_radius: 0.5  #[m]

z_max: 0.5         #[m] 
z_ground: -0.2

v_max: 1.4         #[m/s]  
a_max: 1.4         #[m/s2] 
j_max: 5.0         #[m/s3]

is_ground_robot: true  

And finally open 4 terminals and execute these commands

roslaunch faster ground_robot.launch
roslaunch global_mapper_ros global_mapper_node.launch quad:=JA01
roslaunch faster faster_interface.launch quad:=JA01 is_ground_robot:=true
roslaunch faster faster.launch quad:=JA01

Now you can click Start in the GUI, and then, in RVIZ, press G (or click the option 2D Nav Goal on the top bar of RVIZ) and click any goal for the ground robot.

Architecture:

For the aerial robot, the option 3 is provided (a perfect tracker and a Gazebo simulation to obtain the depth). To make the simulation faster, the physics engine of Gazebo is disabled using disable_physics.cpp of acl-gazebo.

For the ground robot, the option 2 is provided (a controller, and a Gazebo simulation with both dynamics and depth (using the multi_jackal package)

How do I use FASTER with a real robot?

To run the mapper, you simply need to run the node that publishes the depth image of the camera (for example using realsense-ros if you are using an Intel RealSense camera). After launching this node, find the name of the topic of the depth image (by doing rostopic echo), and finally put that name on the launch file of the mapper.

As shown in the diagram above, the UAV should subscribe to the Goal message published by FASTER. The estimator (or the motion capture) should then publish the current state of the UAV as a State message. If you are using a ground robot, you need to publish a nav_msgs/Odometry message (see this), and it will be converted directly to a State message.

Credits:

This package uses code from the JPS3D and DecompROS repos (included in the thirdparty folder), so credit to them as well.

Issues when installing Gurobi:

If you find the error:

“gurobi_continuous.cpp:(.text.startup+0x74): undefined reference to
`GRBModel::set(GRB_StringAttr, std::__cxx11::basic_string<char,
std::char_traits<char>, std::allocator<char> > const&)'”

The solution is:

cd /opt/gurobi800/linux64/src/build  #Note that the name of the folder gurobi800 changes according to the Gurobi version
sudo make
sudo cp libgurobi_c++.a ../../lib/

Issues with other possible errors:

You can safely ignore these terminal errors:

  • Error in REST request (when using ROS Melodic)
  • [ERROR] [...]: GazeboRosControlPlugin missing <legacyModeNS> while using DefaultRobotHWSim, defaults to true. (when using the ground robot)
  • [ERROR] [...]: No p gain specified for pid. Namespace: /gazebo_ros_control/pid_gains/front_left_wheel. (when using the ground robot)

faster's People

Contributors

btlopez avatar dkkim93 avatar jtorde avatar kotakondo avatar mrkris13 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  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  avatar  avatar  avatar  avatar

faster's Issues

global_mapper_ros failed to reconstruct

Hi, The "roslaunch global_mapper_ros global_mapper_node.launch" seems not work properly at my end.

image

One resulting effect is that after I run rviz, no occupancy grids are shown.

I checked the topic "/SQ01s/camera/depth/image_rect_raw" and the depth information has already been published there, which means the perfect_tracker_and_sim should be working properly.

The only evidence I catch in the terminal is a warning of the asynchronization in world_database_master_ros, but this warning does not persist (only appear at the beginning section of outputs)

Could you please help me to fix the global_mapper_ros? Thanks much!

cannot import name libqt_gui_cpp_shiboken

ubuntu18.04
conda 环境 python2.7
ros melodic
File "/opt/ros/melodic/lib/python2.7/dist-packages/qt_gui_cpp/cpp_binding_helper.py", line 39, in from . import libqt_gui_cpp_shiboken ImportError: cannot import name libqt_gui_cpp_shiboken
这个该怎么解决?

Issue with ROS noetic

build.make.005.log

Attaching the build log file. The create_random_forest.cpp file generates a boost library error. There are a lot of issues with noetic, boost, and Ubuntu 20.04. Is there a way to remove these dependencies?

Faster in 3D

Hi,

Is it possible to use faster as a 3D planning algorithm for a drone, so that it can evade obstacles vertically? I have tried faster in a couple of worlds and it seems like it plans only in a plane towards the goal, and doesn't deviate it's height from that plane? I have used faster with the default values as given in the faster.yaml file, and only changed the maximum z coordinate (z_max) to a height that fits to my worlds.

Best wishes,
Karolin

Goal yaw

Hi, I want to share a video about a Gazebo+PX4 SITL simulation where the drone avoids a part of obstacles and impacts one:
https://youtu.be/kiCl-1SBb7Y

The behavior is different from time to time but it seems to me that the yaw settings are never correct. It seems to me that there is too much rotations.
Probably I do something wrong in the transformation.

My controller posts a message to /state with the odometry (which comes from PX4 via /mavros/local_position/odom).
The transformation between base_link and world is done by PX4 (the EKF2 estimator).

uav_state = State()
uav_state.header.frame_id = "world"
uav_state.pos.x = self.current_odom.pose.pose.position.x
uav_state.pos.y = self.current_odom.pose.pose.position.y
uav_state.pos.z = self.current_odom.pose.pose.position.z
uav_state.quat.x = self.current_odom.pose.pose.orientation.x
uav_state.quat.y = self.current_odom.pose.pose.orientation.y
uav_state.quat.z = self.current_odom.pose.pose.orientation.z
uav_state.quat.w = self.current_odom.pose.pose.orientation.w
uav_state.vel.x = self.current_odom.twist.twist.linear.x
uav_state.vel.y = self.current_odom.twist.twist.linear.y
uav_state.vel.z = self.current_odom.twist.twist.linear.z
self.uav_state_pub.publish(uav_state)

and the controller receives the message /goalx from faster (type Goal) and publishes a PoseStamped message to: /mavros/setpoint_position/local:

self.desired_position.pose.position.x = data.p.x
self.desired_position.pose.position.y = data.p.y
self.desired_position.pose.position.z = data.p.z
q = quaternion_from_euler(0, 0, data.yaw)
self.desired_position.pose.orientation.x = q[0]
self.desired_position.pose.orientation.y = q[1]
self.desired_position.pose.orientation.z = q[2]
self.desired_position.pose.orientation.w = q[3]

... publish...

No solution found for the safe path, but the obstacle is still far away.

As shown in the following screenshot, after taking off, the drone is given a goal command by "rostopic pub /move_base_simple/goal geometry_msgs/PoseStamped '{header: {stamp: now, frame_id: "map"}, pose: {position: {x: 10.0, y: 0.0, z: 1.319}, orientation: {w: 1.0}}}'" However, the drone can not move forward because of "No solution found for the safe path". But it appears that the obstacle is still far away from the drone. Could you please help to point out the reason why calculating the safe path is infeasible by FASTER? Thanks much!

image

image

Choosing the Optimal 3D Planner for UAV Autonomous Exploration in Cluttered Environments

Hi there!
First, thank you for the great work and for opening it up for the community.

I'm currently exploring different UAV 3D planners for use in autonomous exploration in cluttered environments. I've come across several planners like Faster, Mader, FastPlanner (https://github.com/HKUST-Aerial-Robotics/Fast-Planner), FUEL (https://github.com/HKUST-Aerial-Robotics/FUEL), and EGO-Planner or EGO Swarm (https://github.com/ZJU-FAST-Lab/ego-planner-swarm). Each of these has its implementation and approach, yet they share a similar goal in terms of the overall objective.

I'm interested in understanding the key differences between these planners. If you had to choose one for an autonomous exploration task in a cluttered environment, which one would it be and why? Are there other planners, perhaps newer or less known, that you would recommend for such applications?

Additionally, I'm curious about the integration of depth sensing in these systems. RGB-D cameras like the Realsense series are commonly used, but what about the potential of LIDAR or time-of-flight (TOF) sensors for more accurate SLAM? For example, the TOF sensors and their lightweight nature could offer extended flight times, which seems particularly beneficial.

Any insights or recommendations you have would be incredibly helpful!

Thanks a lot!

NameError: global name 'QuadGoal' is not defined

Hi,I used faster on the ground robot,but there is such a mistake:

rospy.Subscriber("goal", QuadGoal, c.goalCB, queue_size=1)
NameError: global name 'QuadGoal' is not defined

Do you know the possible causes of this problem? Thanks a lot.

Running FASTER in a world where the ground is positioned under the coordinate origin (z<0)

Hi @jtorde,
I am trying to run FASTER in a world that has a ground plane with position z<0 and parallel to the x-y-plane. When starting the quad from (z,y,z)=(0,0,1) and giving it the goal (z,y,z)=(20,0,-1) it will begin a downward trajectory until it has reached z=0 and fly on the x-y-plane until it is near the goal when, again, it will move down towards the goal and reach it.
When the quad already has a position with its z component <0 FASTER won't re-plan and display:

state_initialized_= 1state_initialized_= 
kdtree_map_initialized_= 0
kdtree_unk_initialized_= 1
terminal_goal_initialized_= 1
Not publishing new goal!!

Sometimes though, it will hover exactly over the goal at z=0 and the FASTER terminal will display:

************IN REPLAN CB*********
Occupancy Grid received is empty, maybe map is too small?
NeedToComputeSafePath=0

I ran these tests with line 8 set to false and line 18 set to -20 in faster.yaml.
This was not the case for goals with z>=0 where the algorithm followed an optimal trajectory when moving upwards or downwards.
I would appreciate any help!

snapstack_msgs missing

How to solve this one (when run catkin build)

CMake Error at /opt/ros/kinetic/share/catkin/cmake/catkinConfig.cmake:83 (find_package):
  Could not find a package configuration file provided by "snapstack_msgs"

by the way, when I run wstool update -j8, I got:

Singularity> wstool update -j8
[acl-gazebo] Fetching https://gitlab.com/mit-acl/lab/acl-gazebo (version ce65ebe64b627a46204c090448971092be3a7154) to /home/tutuzi/ws/src/acl-gazebo
[acl-gazebo,acl-mapping,behavior_selector,catkin_simple,snapstack_msgs] still active
[acl-mapping] Fetching https://gitlab.com/mit-acl/lab/acl-mapping (version 821655dc687cfeec6d4818b73d7633fc5b665987) to /home/tutuzi/ws/src/acl-mapping
[behavior_selector] Fetching https://gitlab.com/mit-acl/fsw/behavior_selector (version 304975f49a726bdbee1f5bdfed5d1943e9eb349e) to /home/tutuzi/ws/src/behavior_selector
[snapstack_msgs] Fetching https://gitlab.com/mit-acl/fsw/snap-stack/snapstack_msgs.git (version 3e1dee9616bd7e8a467bce5a66c947ebf13a79d8) to /home/tutuzi/ws/src/snapstack_msgs
[catkin_simple] Fetching https://github.com/catkin/catkin_simple.git (version 0e62848b12da76c8cc58a1add42b4f894d1ac21e) to /home/tutuzi/ws/src/catkin_simple
Cloning into '/home/tutuzi/ws/src/acl-mapping'...
Cloning into '/home/tutuzi/ws/src/acl-gazebo'...
Cloning into '/home/tutuzi/ws/src/behavior_selector'...
Cloning into '/home/tutuzi/ws/src/snapstack_msgs'...
Cloning into '/home/tutuzi/ws/src/catkin_simple'...
remote: Enumerating objects: 286, done.
remote: Total 286 (delta 0), reused 0 (delta 0), pack-reused 286
Receiving objects: 100% (286/286), 47.72 KiB | 0 bytes/s, done.
Resolving deltas: 100% (108/108), done.
Checking connectivity... done.
[catkin_simple] Done.
[acl-gazebo,acl-mapping,behavior_selector,snapstack_msgs] still active
[acl-gazebo,acl-mapping,behavior_selector,snapstack_msgs] still active
[acl-gazebo,acl-mapping,behavior_selector,snapstack_msgs] still active
[acl-gazebo,acl-mapping,behavior_selector,snapstack_msgs] still active
[acl-gazebo,acl-mapping,behavior_selector,snapstack_msgs] still active
fatal: unable to access 'https://gitlab.com/mit-acl/fsw/behavior_selector/': Failed to connect to gitlab.com port 443: Connection refused
fatal: unable to access 'https://gitlab.com/mit-acl/lab/acl-gazebo/': Failed to connect to gitlab.com port 443: Connection refused
fatal: unable to access 'https://gitlab.com/mit-acl/fsw/snap-stack/snapstack_msgs.git/': Failed to connect to gitlab.com port 443: Connection refused
fatal: unable to access 'https://gitlab.com/mit-acl/lab/acl-mapping/': Failed to connect to gitlab.com port 443: Connection refused
Exception caught during install: Error processing 'acl-gazebo' : [acl-gazebo] Checkout of https://gitlab.com/mit-acl/lab/acl-gazebo version ce65ebe64b627a46204c090448971092be3a7154 into /home/tutuzi/ws/src/acl-gazebo failed.
Error processing 'acl-mapping' : [acl-mapping] Checkout of https://gitlab.com/mit-acl/lab/acl-mapping version 821655dc687cfeec6d4818b73d7633fc5b665987 into /home/tutuzi/ws/src/acl-mapping failed.
Error processing 'behavior_selector' : [behavior_selector] Checkout of https://gitlab.com/mit-acl/fsw/behavior_selector version 304975f49a726bdbee1f5bdfed5d1943e9eb349e into /home/tutuzi/ws/src/behavior_selector failed.
Error processing 'snapstack_msgs' : [snapstack_msgs] Checkout of https://gitlab.com/mit-acl/fsw/snap-stack/snapstack_msgs.git version 3e1dee9616bd7e8a467bce5a66c947ebf13a79d8 into /home/tutuzi/ws/src/snapstack_msgs failed.

ERROR in config: Error processing 'acl-gazebo' : [acl-gazebo] Checkout of https://gitlab.com/mit-acl/lab/acl-gazebo version ce65ebe64b627a46204c090448971092be3a7154 into /home/tutuzi/ws/src/acl-gazebo failed.
Error processing 'acl-mapping' : [acl-mapping] Checkout of https://gitlab.com/mit-acl/lab/acl-mapping version 821655dc687cfeec6d4818b73d7633fc5b665987 into /home/tutuzi/ws/src/acl-mapping failed.
Error processing 'behavior_selector' : [behavior_selector] Checkout of https://gitlab.com/mit-acl/fsw/behavior_selector version 304975f49a726bdbee1f5bdfed5d1943e9eb349e into /home/tutuzi/ws/src/behavior_selector failed.
Error processing 'snapstack_msgs' : [snapstack_msgs] Checkout of https://gitlab.com/mit-acl/fsw/snap-stack/snapstack_msgs.git version 3e1dee9616bd7e8a467bce5a66c947ebf13a79d8 into /home/tutuzi/ws/src/snapstack_msgs failed.

ERROR

hi developer!
when i try run roslaunch faster faster.launch

i got this error:

Screenshot from 2020-12-10 13-14-53

@jtorde could you help me?

edit:
roslaunch acl_sim start_world.launch roslaunch acl_sim perfect_tracker_and_sim.launch roslaunch global_mapper_ros global_mapper_node.launch roslaunch faster faster_interface.launch roslaunch faster faster.launch

I can successfully run the first four commands

Error

Hello, when I use catkin build, I encounter the following warnings and errors.

Warnings << acl_sim:cmake /home/vboxuser/faster/logs/acl_sim/build.cmake.001.log
CMake Warning (dev) at /usr/share/cmake-3.10/Modules/FindBoost.cmake:911 (if):
Policy CMP0054 is not set: Only interpret if() arguments as variables or
keywords when unquoted. Run "cmake --help-policy CMP0054" for policy
details. Use the cmake_policy command to set the policy and suppress this
warning.

Quoted variables like "chrono" will no longer be dereferenced when the
policy is set to NEW. Since the policy is not set the OLD behavior will be
used.
Call Stack (most recent call first):
/usr/share/cmake-3.10/Modules/FindBoost.cmake:1558 (_Boost_MISSING_DEPENDENCIES)
/usr/share/OGRE/cmake/modules/FindOGRE.cmake:318 (find_package)
/usr/lib/x86_64-linux-gnu/cmake/gazebo/gazebo-config.cmake:175 (find_package)
CMakeLists.txt:21 (find_package)
This warning is for project developers. Use -Wno-dev to suppress it.

Errors << decomp_ros_utils:make /home/vboxuser/faster/logs/decomp_ros_utils/build.make.001.log
c++: internal compiler error: Killed (program cc1plus)
Please submit a full bug report,
with preprocessed source if appropriate.
See file:///usr/share/doc/gcc-7/README.Bugs for instructions.
make[2]: *** [CMakeFiles/decomp_rviz_plugins.dir/src/polyhedron_array_display.cpp.o] Error 4
make[1]: *** [CMakeFiles/decomp_rviz_plugins.dir/all] Error 2
make: *** [all] Error 2

Any help on this would be appreciated, thanks!

mapping

Hello I want to know your mapping algorithm (realtime) in your flying

Error

hello developer:
when I run compile the code: catkin build
it shows some problems:

/usr/include/ignition/msgs1/ignition/msgs/fog.pb.h:235:33: error: ‘InternalMetadataWithArena’ in namespace ‘google::protobuf::internal’ does not name a type
::google::protobuf::internal::InternalMetadataWithArena internal_metadata;
^~~~~~~~~~~~~~~~~~~~~~~~~
/usr/include/ignition/msgs1/ignition/msgs/fog.pb.h: In member function ‘const google::protobuf::UnknownFieldSet& ignition::msgs::Fog::unknown_fields() const’:
/usr/include/ignition/msgs1/ignition/msgs/fog.pb.h:89:12: error: ‘internal_metadata’ was not declared in this scope
return internal_metadata.unknown_fields();
^~~~~~~~~~~~~~~~~~~
/usr/include/ignition/msgs1/ignition/msgs/fog.pb.h: In member function ‘google::protobuf::UnknownFieldSet* ignition::msgs::Fog::mutable_unknown_fields()’:
/usr/include/ignition/msgs1/ignition/msgs/fog.pb.h:93:12: error: ‘internal_metadata’ was not declared in this scope
return internal_metadata.mutable_unknown_fields();
^~~~~~~~~~~~~~~~~~~
/usr/include/ignition/msgs1/ignition/msgs/fog.pb.h: In member function ‘google::protobuf::Arena* ignition::msgs::Fog::GetArenaNoVirtual() const’:
/usr/include/ignition/msgs1/ignition/msgs/fog.pb.h:131:12: error: ‘internal_metadata’ was not declared in this scope
return internal_metadata.arena();
^~~~~~~~~~~~~~~~~~~
/usr/include/ignition/msgs1/ignition/msgs/fog.pb.h: In member function ‘void* ignition::msgs::Fog::MaybeArenaPtr() const’:
/usr/include/ignition/msgs1/ignition/msgs/fog.pb.h:134:12: error: ‘internal_metadata’ was not declared in this scope
return internal_metadata.raw_arena_ptr();
^~~~~~~~~~~~~~~~~~~
How to solve this problem? Thanks.

How to programmatically set goal point for drone

Hi, great work on this novel planner! I was wondering whether if there is a way to easily set the goal point for the planner without having to click a point in Rviz? I wanted to perform some repeatable experiments with a constant goal point. Will publishing on the /SQ01s/goal topic do the trick or is there a way to do this in the existing code base that I am unaware of?

Thanks!

rvize & gazebo

Hi, could you please help me?
I've done all the installation and compilation, but I can't see any drones in rviz or gazebo (I can set up 2D Nav Goal).

image

snapstack_msgs::Goal QuadGoal has still a problem

Hello MIT-ACL team,

I've been trying to install FASTER and this issue occured :

Errors     << faster:make /home/fmukwege/workspace/logs/faster/build.make.001.log
/home/fmukwege/workspace/src/faster/faster/src/faster_ros.cpp: In member function ‘void FasterRos::pubCB(const ros::TimerEvent&)’:
/home/fmukwege/workspace/src/faster/faster/src/faster_ros.cpp:272:47: error: no match for ‘operator=’ (operand types are ‘snapstack_msgs::Goal_<std::allocator<void> >::_p_type {aka geometry_msgs::Point_<std::allocator<void> >}’ and ‘geometry_msgs::Vector3 {aka geometry_msgs::Vector3_<std::allocator<void> >}’)
     quadGoal.p = eigen2rosvector(next_goal.pos);
                                               ^
In file included from /opt/ros/melodic/include/geometry_msgs/PointStamped.h:19:0,
                 from /home/fmukwege/workspace/src/faster/faster/include/faster_ros.hpp:11,
                 from /home/fmukwege/workspace/src/faster/faster/src/faster_ros.cpp:9:
/opt/ros/melodic/include/geometry_msgs/Point.h:22:8: note: candidate: geometry_msgs::Point_<std::allocator<void> >& geometry_msgs::Point_<std::allocator<void> >::operator=(const geometry_msgs::Point_<std::allocator<void> >&)
 struct Point_
        ^~~~~~
/opt/ros/melodic/include/geometry_msgs/Point.h:22:8: note:   no known conversion for argument 1 from ‘geometry_msgs::Vector3 {aka geometry_msgs::Vector3_<std::allocator<void> >}’ to ‘const geometry_msgs::Point_<std::allocator<void> >&’
/opt/ros/melodic/include/geometry_msgs/Point.h:22:8: note: candidate: geometry_msgs::Point_<std::allocator<void> >& geometry_msgs::Point_<std::allocator<void> >::operator=(geometry_msgs::Point_<std::allocator<void> >&&)
/opt/ros/melodic/include/geometry_msgs/Point.h:22:8: note:   no known conversion for argument 1 from ‘geometry_msgs::Vector3 {aka geometry_msgs::Vector3_<std::allocator<void> >}’ to ‘geometry_msgs::Point_<std::allocator<void> >&&’
/home/fmukwege/workspace/src/faster/faster/src/faster_ros.cpp:276:14: error: ‘snapstack_msgs::Goal {aka struct snapstack_msgs::Goal_<std::allocator<void> >}’ has no member named ‘dyaw’
     quadGoal.dyaw = next_goal.dyaw;
              ^~~~
/home/fmukwege/workspace/src/faster/faster/src/faster_ros.cpp:277:14: error: ‘snapstack_msgs::Goal {aka struct snapstack_msgs::Goal_<std::allocator<void> >}’ has no member named ‘yaw’
     quadGoal.yaw = next_goal.yaw;
              ^~~
make[2]: *** [CMakeFiles/faster_node.dir/src/faster_ros.cpp.o] Error 1
make[1]: *** [CMakeFiles/faster_node.dir/all] Error 2
make: *** [all] Error 2

I saw someone had this issue in issue #23 and thus I have cloned the lastest snapstack_msgs commit (1ecc836425f11acfa9c78f18dd22488b7783a852) but nothing changed

What could be the problem ?

Best regards,

Frank

Can you help me with a problem happend during building?

I encountered the following problem

CMake Error at /usr/share/cmake-3.10/Modules/FindPackageHandleStandardArgs.cmake:137 (message):
  Could NOT find GUROBI (missing: GUROBI_LIBRARY)

I think I followed all the instructions correctly and the file ~/.bashrc is appended with the following statements:

source /opt/ros/melodic/setup.bash
export GUROBI_HOME="/home/zjnyly/Desktop/gurobi911/linux64"
export PATH="${PATH}:${GUROBI_HOME}/bin"
export LD_LIBRARY_PATH="${LD_LIBRARY_PATH}:${GUROBI_HOME}/lib"
export GRB_LICENSE_FILE="/home/zjnyly/gurobi.lic"
source /home/zjnyly/Desktop/ws//devel/setup.bash

I then tried to change the version of gurobi manully in FindGUROBI.cmake file, but I don't know how to correctly write it.
(the version of gurobi on my computer is 9.1.1.

find_library(GUROBI_LIBRARY
NAMES gurobi gurobi91
HINTS ${GUROBI_DIR} $ENV{GUROBI_HOME}
PATH_SUFFIXES lib)

I'm new to this field and I don't know much about these things. I'd appreciate it if you could help me. Thanks!

protobuf version conflict

My system is ubuntu16.04 gazebo8 and protobuf version is 3.6
When using FASTER with an aerial robot
the step catkin build runs, and the errors occur as follows:

 #error regenerate this file with a newer version of protoc.
 #error regenerate this file with a newer version of protoc.
  ^
In file included from /usr/include/ignition/msgs0/ignition/msgs/geometry.pb.h:30:0,
                 from /usr/include/ignition/msgs0/ignition/msgs/collision.pb.h:28,
                 from /usr/include/ignition/msgs0/ignition/msgs/MessageTypes.hh:16,
                 from /usr/include/ignition/msgs0/ignition/msgs.hh:3,
                 from /usr/include/ignition/transport3/ignition/transport/Node.hh:32,
                 from /usr/include/gazebo-8/gazebo/physics/Entity.hh:25,
                 from /usr/include/gazebo-8/gazebo/physics/Model.hh:30,
                 from /usr/include/gazebo-8/gazebo/physics/Actor.hh:24,
                 from /usr/include/gazebo-8/gazebo/physics/physics.hh:2,
                 from /home/yjq/program/uav_ws/src/acl-gazebo/acl_sim/src/disable_physics_kinetic.cpp:4:
/usr/include/ignition/msgs0/ignition/msgs/cylindergeom.pb.h:17:2: error: #error This file was generated by an older version of protoc which is
 #error This file was generated by an older version of protoc which is
  ^
/usr/include/ignition/msgs0/ignition/msgs/cylindergeom.pb.h:18:2: error: #error incompatible with your Protocol Buffer headers. Please
 #error incompatible with your Protocol Buffer headers.  Please
  ^
/usr/include/ignition/msgs0/ignition/msgs/cylindergeom.pb.h:19:2: error: #error regenerate this file with a newer version of protoc.
 #error regenerate this file with a newer version of protoc.

Which version should the protobuf is?
Thank you sooo much for your reply.

nlopt

Hi,
Can FASTER be used with NLOPT instead of Gurobi?

roslaunch faster faster_interface.launch quad:=JA01 is_ground_robot:=true show "Not initialized yet"

Hi, @jtorde
I wanted to use this code on the ground robot, but I ran into a problem in the simulation. But when i didn't change the is_ground_robot (still set true) parameters in faster.yaml, I found UAV simulation can run well....

I follow the steps to configure and type four commands ,and then click the three buttons in the gui that show "Not initialized yet".
Then there is no message generated or sent by goal or cmd_vel.

Terminal display information :

... logging to /home/ysz/.ros/log/55eb0e4c-bac2-11ea-b734-000c29a4c471/roslaunch-ysz-35817.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://ysz:43171/

SUMMARY

PARAMETERS

  • /JA01/faster_commands/is_ground_robot: True
  • /rosdistro: kinetic
  • /rosversion: 1.12.14

NODES
/
rqt_gui (rqt_gui/rqt_gui)
rviz (rviz/rviz)
/JA01/
faster_commands (faster/faster_commands.py)

ROS_MASTER_URI=http://localhost:11311

process[JA01/faster_commands-1]: started with pid [35835]
process[rviz-2]: started with pid [35836]
process[rqt_gui-3]: started with pid [35837]
('self.is_ground_robot=', True)

(when I click the button in the gui)
Not initialized yet
Not initialized yet
Not initialized yet
Not initialized yet

Gazebo+PX4-SITL implementation problem

I'm having trouble implementing faster on a Gazebo+PX4 SITL simulation.
I have my world and a Iris model.
I implemented a controller in python (option 2 of the architecture) but when I subscribe the /goal topic I get:

[ERROR] [1633099445.913813448]: Client [/Extars_Supervisor] wants topic /goal to have datatype/md5sum [snapstack_msgs/Goal/29f7a5b62089bdabd9ea1780f356bc8b], but our version has [geometry_msgs/PoseStamped/d3812c3cbc69362b77dc0b19b345f8f5]. Dropping connection.

I have deleted the workspace and recompiled several times but to no avail.
On the whole disk as a Goal message definition I have these in my workspace:

./home/robot/extars/extars_ws/devel/.private/snapstack_msgs/lib/python2.7/dist-packages/snapstack_msgs/msg/_Goal.py
./home/robot/extars/extars_ws/devel/lib/python2.7/dist-packages/snapstack_msgs/msg/_Goal.py

Does anyone have an idea?

faster has died with GRBException

Hello, during a simulated mission if I provide a waypoint beyond a wall I always get this error.
I have Gurobi version 9.12 installed on my system. Can this be a problem?

Schermata da 2021-10-04 17-52-08
rviz_screenshot_2021_10_04-17_59_21
default_gzclient_camera(1)-2021-10-04T17_59_02 938044

Implement PX4 OFFBOARD

I am very interested in learning about this project.
Hello, I see #14 and I was wondering if someone could kindly show me an example of a controller to translate the trajectories processed by the planner into messages compatible with the OFFBOARD mode of PX4.
Even a similar example can be helpful.
Thank you.

How to programmatically send signals to the Faster GUI?

Hi developers, I'm wondering instead of manually clicking on the "Start", "Stop" Emergency Stop" buttons in the Faster GUI every time we start/stop the drone, is there a way to programmatically enable those signals like using a python script?

can not open the cvx_JA01.rviz

thanks for your great work.
i have met the problem that i can not open the cvx_JA01.rviz,while i can open the cvx_SQ01s.rviz. i doubt it whether the orbt is wrong number,so i changed the last three lines to Width: 2495
X: 19.85
Y: 24
then i can open it ,however,i can not plan ,when i clicked the start button,the command window shows"Not initialized yet"
i run it in ubuntu16,ros-kinetic.
how do i solve it?thank you very much

Cannot run the second :roslaunch acl_sim perfect_tracker_and_sim.launch

Hello!
When I run the second :roslaunch acl_sim perfect_tracker_and_sim.launch,I meet error:

... logging to /home/gyl/.ros/log/2af5c044-8e6d-11ec-a867-bcf1718f8dce/roslaunch-gyl-Lenovo-31967.log
Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

resource not found: hector_sensors_description
ROS path [0]=/opt/ros/melodic/share/ros
ROS path [1]=/home/gyl/ROS_Projects/FASTER/src/acl-gazebo/acl_sim
ROS path [2]=/home/gyl/ROS_Projects/FASTER/src/behavior_selector
ROS path [3]=/home/gyl/ROS_Projects/FASTER/src/catkin_simple
ROS path [4]=/home/gyl/ROS_Projects/FASTER/src/faster/thirdparty/DecompROS/decomp_ros_msgs
ROS path [5]=/home/gyl/ROS_Projects/FASTER/src/faster/thirdparty/DecompROS/DecompUtil
ROS path [6]=/home/gyl/ROS_Projects/FASTER/src/faster/thirdparty/DecompROS/decomp_ros_utils
ROS path [7]=/home/gyl/ROS_Projects/FASTER/src/faster/thirdparty/DecompROS/decomp_test_node
ROS path [8]=/home/gyl/ROS_Projects/FASTER/src/faster/faster_msgs
ROS path [9]=/home/gyl/ROS_Projects/FASTER/src/acl-mapping/fla_msgs
ROS path [10]=/home/gyl/ROS_Projects/FASTER/src/acl-mapping/fla_utils
ROS path [11]=/home/gyl/ROS_Projects/FASTER/src/acl-mapping/depthmap_filter
ROS path [12]=/home/gyl/ROS_Projects/FASTER/src/acl-mapping/global-mapper/global_mapper
ROS path [13]=/home/gyl/ROS_Projects/FASTER/src/faster/thirdparty/jps3d
ROS path [14]=/home/gyl/ROS_Projects/FASTER/src/snapstack_msgs
ROS path [15]=/home/gyl/ROS_Projects/FASTER/src/faster/faster
ROS path [16]=/home/gyl/ROS_Projects/FASTER/src/acl-mapping/global-mapper/global_mapper_ros
ROS path [17]=/home/gyl/ROS_Projects/GYL_ws/Prometheus/Modules/common/msgs
ROS path [18]=/home/gyl/ROS_Projects/GYL_ws/Prometheus/Modules/control
ROS path [19]=/home/gyl/ROS_Projects/GYL_ws/Prometheus/Modules/mission
ROS path [20]=/home/gyl/ROS_Projects/GYL_ws/Prometheus/Modules/slam
ROS path [21]=/home/gyl/ROS_Projects/GYL_ws/Prometheus/Modules/planning
ROS path [22]=/home/gyl/ROS_Projects/GYL_ws/Prometheus/Modules/ground_station
ROS path [23]=/home/gyl/ROS_Projects/GYL_ws/Prometheus/Simulator/gazebo_simulator
ROS path [24]=/home/gyl/ROS_Projects/GYL_ws/Prometheus/Experiment
ROS path [25]=/opt/ros/melodic/share
when processing file: /home/gyl/ROS_Projects/FASTER/src/acl-gazebo/acl_sim/urdf/quadrotor_base.urdf.xacro
included from: /home/gyl/ROS_Projects/FASTER/src/acl-gazebo/acl_sim/urdf/quadrotor_with_asus.urdf.xacro
included from: /home/gyl/ROS_Projects/FASTER/src/acl-gazebo/acl_sim/urdf/quadrotor_with_asus.gazebo.xacro
RLException: while processing /home/gyl/ROS_Projects/FASTER/src/acl-gazebo/acl_sim/launch/spawn_quadrotor_with_asus.launch:
while processing /home/gyl/ROS_Projects/FASTER/src/acl-gazebo/acl_sim/launch/spawn_quadrotor.launch:
Invalid tag: Cannot load command parameter [robot_description]: command [['/opt/ros/melodic/lib/xacro/xacro', '/home/gyl/ROS_Projects/FASTER/src/acl-gazebo/acl_sim/urdf/quadrotor_with_asus.gazebo.xacro', 'base_link_frame:=/base_link', 'world_frame:=world']] returned with code [2].

Param xml is
The traceback for the exception was written to the log file

2022-02-15 22-46-22 的屏幕截图

How to run Faster(aerial) on different maps

Hi developers, I'm new to ROS, and I'm wondering if Faster(aerial robots) also work on other maps?

If so, where can we find those maps? And how could we import maps to the current project? Appreciate the help, thanks!

ERROR: cannot launch node of type

ERROR: cannot launch node of type [faster/faster_node]: can't locate node [faster_node] in package [faster],when I run roslaunch faster faster.launch,how can I solve this problem?

How to run faster when the map is completely known?

Hi, I have read the paper about this trajectory planning algorithm. I'd like to figure out how to run the faster simulation in ros, when the map and obstacles are completely known. Is there any file or code need to be modified? Thanks for your time!

a problem happend during building

I encountered the following problem, but i don't know why,please help me

CMakeFiles/faster_node.dir/src/solverGurobi.cpp.o:在函数‘SolverGurobi::setThreads(int)’中:
solverGurobi.cpp:(.text+0x2270):对‘GRBModel::set(std::__cxx11::basic_string<char, std::char_traits, std::allocator > const&, std::__cxx11::basic_string<char, std::char_traits, std::allocator > const&)’未定义的引用
CMakeFiles/faster_node.dir/src/solverGurobi.cpp.o:在函数‘SolverGurobi::setVerbose(int)’中:
solverGurobi.cpp:(.text+0x2350):对‘GRBModel::set(std::__cxx11::basic_string<char, std::char_traits, std::allocator > const&, std::__cxx11::basic_string<char, std::char_traits, std::allocator > const&)’未定义的引用
CMakeFiles/faster_node.dir/src/solverGurobi.cpp.o:在函数‘SolverGurobi::setMaxConstraints()’中:
solverGurobi.cpp:(.text+0x391e):对‘GRBModel::addConstr(GRBTempConstr const&, std::__cxx11::basic_string<char, std::char_traits, std::allocator >)’未定义的引用
solverGurobi.cpp:(.text+0x3c73):对‘GRBModel::addConstr(GRBTempConstr const&, std::__cxx11::basic_string<char, std::char_traits, std::allocator >)’未定义的引用
solverGurobi.cpp:(.text+0x3fc0):对‘GRBModel::addConstr(GRBTempConstr const&, std::__cxx11::basic_string<char, std::char_traits, std::allocator >)’未定义的引用
solverGurobi.cpp:(.text+0x4315):对‘GRBModel::addConstr(GRBTempConstr const&, std::__cxx11::basic_string<char, std::char_traits, std::allocator >)’未定义的引用
solverGurobi.cpp:(.text+0x4681):对‘GRBModel::addConstr(GRBTempConstr const&, std::__cxx11::basic_string<char, std::char_traits, std::allocator >)’未定义的引用
CMakeFiles/faster_node.dir/src/solverGurobi.cpp.o:solverGurobi.cpp:(.text+0x49f0): 跟着更多未定义的参考到 GRBModel::addConstr(GRBTempConstr const&, std::__cxx11::basic_string<char, std::char_traits, std::allocator >)
CMakeFiles/faster_node.dir/src/solverGurobi.cpp.o:在函数‘SolverGurobi::SolverGurobi()’中:
solverGurobi.cpp:(.text+0x542f):对‘GRBModel::set(GRB_StringAttr, std::__cxx11::basic_string<char, std::char_traits, std::allocator > const&)’未定义的引用
CMakeFiles/faster_node.dir/src/solverGurobi.cpp.o:在函数‘SolverGurobi::setConstraintsXf()’中:
solverGurobi.cpp:(.text+0x5e3c):对‘GRBModel::addConstr(GRBTempConstr const&, std::__cxx11::basic_string<char, std::char_traits, std::allocator >)’未定义的引用
solverGurobi.cpp:(.text+0x5f9f):对‘GRBModel::addConstr(GRBTempConstr const&, std::__cxx11::basic_string<char, std::char_traits, std::allocator >)’未定义的引用
solverGurobi.cpp:(.text+0x60f2):对‘GRBModel::addConstr(GRBTempConstr const&, std::__cxx11::basic_string<char, std::char_traits, std::allocator >)’未定义的引用
CMakeFiles/faster_node.dir/src/solverGurobi.cpp.o:在函数‘SolverGurobi::setConstraintsX0()’中:
solverGurobi.cpp:(.text+0x644e):对‘GRBModel::addConstr(GRBTempConstr const&, std::__cxx11::basic_string<char, std::char_traits, std::allocator >)’未定义的引用
solverGurobi.cpp:(.text+0x6567):对‘GRBModel::addConstr(GRBTempConstr const&, std::__cxx11::basic_string<char, std::char_traits, std::allocator >)’未定义的引用
CMakeFiles/faster_node.dir/src/solverGurobi.cpp.o:solverGurobi.cpp:(.text+0x6678): 跟着更多未定义的参考到 GRBModel::addConstr(GRBTempConstr const&, std::__cxx11::basic_string<char, std::char_traits, std::allocator >)
CMakeFiles/faster_node.dir/src/solverGurobi.cpp.o:在函数‘SolverGurobi::createVars()’中:
solverGurobi.cpp:(.text+0x7a0d):对‘GRBModel::addVar(double, double, double, char, std::__cxx11::basic_string<char, std::char_traits, std::allocator >)’未定义的引用
CMakeFiles/faster_node.dir/src/solverGurobi.cpp.o:在函数‘SolverGurobi::setPolytopesConstraints()’中:
solverGurobi.cpp:(.text+0x8d8d):对‘GRBModel::addVar(double, double, double, char, std::__cxx11::basic_string<char, std::char_traits, std::allocator >)’未定义的引用
solverGurobi.cpp:(.text+0x93fa):对‘GRBModel::addConstr(GRBTempConstr const&, std::__cxx11::basic_string<char, std::char_traits, std::allocator >)’未定义的引用
solverGurobi.cpp:(.text+0xa27c):对‘GRBModel::addGenConstrIndicator(GRBVar, int, GRBLinExpr const&, char, double, std::__cxx11::basic_string<char, std::char_traits, std::allocator >)’未定义的引用
solverGurobi.cpp:(.text+0xa331):对‘GRBModel::addGenConstrIndicator(GRBVar, int, GRBLinExpr const&, char, double, std::__cxx11::basic_string<char, std::char_traits, std::allocator >)’未定义的引用
solverGurobi.cpp:(.text+0xa3d0):对‘GRBModel::addGenConstrIndicator(GRBVar, int, GRBLinExpr const&, char, double, std::__cxx11::basic_string<char, std::char_traits, std::allocator >)’未定义的引用
solverGurobi.cpp:(.text+0xa467):对‘GRBModel::addGenConstrIndicator(GRBVar, int, GRBLinExpr const&, char, double, std::__cxx11::basic_string<char, std::char_traits, std::allocator >)’未定义的引用
collect2: error: ld returned 1 exit status
make[2]: *** [/home/thn/project/cproject/competition/ws/devel/.private/faster/lib/faster/faster_node] Error 1
make[1]: *** [CMakeFiles/faster_node.dir/all] Error 2
make: *** [all] Error 2

tf time error in global mapper

I'm trying to run the path planner for the drone but the global_mapper keeps crashing with the following error.

[ INFO] [1629208100.725128566, 60.234000000]: Mapper:: DepthImage received
[ WARN] [1629208101.020232863, 60.355000000]: [GlobalMapperRos::DepthImageCallback] Lookup would require extrapolation into the past.  Requested time 60.199000000 but the earliest data is at time 60.236000000, when looking up transform from frame [SQ01s/camera] to frame [world]
[ INFO] [1629208101.058313847, 60.370000000]: Mapper:: DepthImage received
[SQ01s/global_mapper_ros-1] process has died [pid 9514, exit code -11, cmd /home/grammers/catkin_ws/sim_path/devel/lib/global_mapper_ros/global_mapper_node ~depth_image_topic:=camera/depth/image_rect_raw ~pose_topic:=state ~goal_topic:=/move_base_simple/goal ~odom_topic:=odometry/filtered_no ~occupancy_grid_topic:=~occupancy_grid ~unknown_grid_topic:=~unknown_grid ~frontier_grid_topic:=~frontier_grid ~distance_grid_topic:=~distance_grid ~cost_grid_topic:=~cost_grid ~path_topic:=~path ~sparse_path_topic:=~sparse_path __name:=global_mapper_ros __log:=/home/grammers/.ros/log/c0b0d182-ff61-11eb-a955-c858c0482128/SQ01s-global_mapper_ros-1.log].
log file: /home/grammers/.ros/log/c0b0d182-ff61-11eb-a955-c858c0482128/SQ01s-global_mapper_ros-1*.log

I'm following the instructions in README.
It looks like a timing issue in tf but I don't know if it is and how to fix it if it is. Any suggestion for a solution? Thanks in advance!

ROS Melodic compatibility changes

I'm trying to get Faster working on my machine with Ubuntu 18.04 and ROS Melodic. What I've changed so far:

  • I installed the "ros-melodic-" dependencies instead of the "ros-kinetic-" dependencies
  • I'm using the "feature/support_ros_melodic" branch of acl-gazebo instead of the "master" branch

With these changes, the workspace builds with the following two warnings:

Warnings   << acl_sim:cmake /home/user/faster_ws/logs/acl_sim/build.cmake.000.log
CMake Warning (dev) at /usr/share/cmake-3.10/Modules/FindBoost.cmake:911 (if):
  Policy CMP0054 is not set: Only interpret if() arguments as variables or
  keywords when unquoted.  Run "cmake --help-policy CMP0054" for policy
  details.  Use the cmake_policy command to set the policy and suppress this
  warning.

  Quoted variables like "chrono" will no longer be dereferenced when the
  policy is set to NEW.  Since the policy is not set the OLD behavior will be
  used.
Call Stack (most recent call first):
  /usr/share/cmake-3.10/Modules/FindBoost.cmake:1558 (_Boost_MISSING_DEPENDENCIES)
  /usr/share/OGRE/cmake/modules/FindOGRE.cmake:318 (find_package)
  /usr/lib/x86_64-linux-gnu/cmake/gazebo/gazebo-config.cmake:175 (find_package)
  CMakeLists.txt:21 (find_package)
This warning is for project developers.  Use -Wno-dev to suppress it.

and

Warnings   << decomp_ros_utils:cmake /home/user/faster_ws/logs/decomp_ros_utils/build.cmake.000.log
CMake Warning at /opt/ros/melodic/share/catkin/cmake/catkin_package.cmake:166 (message):
  catkin_package() DEPENDS on 'decomp_util' but neither
  'decomp_util_INCLUDE_DIRS' nor 'decomp_util_LIBRARIES' is defined.
Call Stack (most recent call first):
  /opt/ros/melodic/share/catkin/cmake/catkin_package.cmake:102 (_catkin_package)
  /home/user/faster_ws/devel/share/catkin_simple/cmake/catkin_simple-extras.cmake:214 (catkin_package)
  CMakeLists.txt:46 (cs_export)

For the aerial robot, when I press "START", it takes off, but when I give it a nav goal, nothing happens.
The last thing that prints in the terminal where I ran roslaunch faster faster.launch is

[ INFO] [1589819914.036287779]: Waiting for world to camera transform...

The terminal where I ran roslaunch global_mapper_ros global_mapper_node.launch has this persistent warning:

[ WARN] [1589820037.314969058, 135.148000000]: [world_database_master_ros] OnGetTransform failed with "Q01s" passed to lookupTransform argument source_frame does not exist. 

In the terminal where I ran roslaunch acl_sim start_world.launch has an error:

[Err] [REST.cc:205] Error in REST request

libcurl: (51) SSL: no alternative certificate subject name matches target host name 'api.ignitionfuel.org'

and a warning:

[ WARN] [1589819857.395608542, 66.828000000]: dynamic reconfigure is not enabled for this image topic [camera/rgb/image_raw] becuase <cameraName> is not specified

Similarly, when I try running the ground robot, the robot never moves after I send nav goals.
The last thing that prints in the terminal where I ran roslaunch faster faster.launch quad:=JA01 is

[ INFO] [1589819442.228136026]: Waiting for world to camera transform...

There's this repeated warning in the terminal where I ran roslaunch global_mapper_ros global_mapper_node.launch quad:=JA01

[ WARN] [1589819328.864921609, 63.361000000]: [world_database_master_ros] OnGetTransform failed with "A01" passed to lookupTransform argument source_frame does not exist. 

The terminal where I ran roslaunch faster ground_robot.launch has the same REST request error and dynamic reconfigure warning as the aerial vehicle.

I appreciate any suggestions you have for me!

I used faster on the ground robot, but the replanning process always failed

Hi, I want to use FASTER on the ground robot. And I run the "roslaunches" according to the exact procedure.
When I first click the "start" and give the goal by "2D Nave Goal", it runs well and reached the destination.
But for the next goal, it always fails and the car is swaying in the simulation environment.

Do you know the possible causes of this problem? Thanks a lot.
What's more, I'd like to know how the car knows its exact real-time position. Thanks again!

Running the mapper on a real Jackal robot

Hi - I'm trying to run the planner on a Jackal robot, following the instructions for running on a real robot, but am having some trouble getting the mapper to work. When I run the mapper (using global_mapper_node.launch), I get the persistent warning

[ WARN] [1619028102.660679293]: [world_database_master_ros] OnGetTransform failed with "JA01" passed to lookupTransform argument source_frame does not exist.

and the mapper doesn't publish anything to the occupancy grid topics.

The topics and tf frames published by my Jackal don't use any top-level namespace, which seems like it may be causing the issue (e.g. it just publishes to "odometry/filtered" rather than "JA01/odometry/filtered", or some other namespace that I could use for the "quad" argument in the launch file). How can I restructure things to make the mapper compatible with my Jackal robot?

Appreciate any help with this, and thanks for your work making this code available!


Some more info on my setup:

  • I'm using depth images from a ZED2 stereo camera mounted on the Jackal, and am using a vicon system to get the ground truth pose of the robot.
  • The ZED2 node publishes a transform from the "world" frame to the "odom" frame used by the Jackal.
  • In the global_mapper_node.launch file, I set the depth_image_topic to the depth image topic published by the ZED2 node, and set the odom_topic to the Jackal's filtered odometry. I'm running the launch file with the quad argument set to JA01.
  • For publishing the robot state: I wrote a script that subscribes to the vicon topic and the Jackal's filtered odometry topic, replaces the pose in the odometry messages with the ground truth pose from the vicon, and republishes the result (as type nav_msgs/Odometry) on the "ground_truth/state" topic.

Also, here's my tf tree in case this helps: frames_jackal.pdf

Error

ERROR: cannot launch node of type [global_mapper_ros/global_mapper_node]: Cannot locate node of type [global_mapper_node] in package [global_mapper_ros]. Make sure file exists in package path and permission is set to executable (chmod +x)
No processes to monitor

when I run roslaunch global_mapper_ros global_mapper_node.launch...
how can I solve this problem?

Wrong findGUROBI

find_library( GUROBI_LIBRARY

In the findGUROBI, both GUROBI_LIBRARY and GUROBI_CXX_LIBRARY matches to same libgurobi_c++.a as same pattern is present in both. This results to not linking of .so files eg. libgurobi91.so. This leads to undefined reference errors in gurobi.

FASTER with Dynamic Obstacles

Hi, this is not an issue per-se, but I was wondering if there's an approach which could be used to introduce dynamic obstacle handling into this framework.

Apologies if there is a better forum for this.

how to use faster

when I take the 2D navigation point , it looks like that this algorithm always only spiralling and can't go to the desination.
Does somebody have the same problem?

RVIZ No fixed frame [world] Problem

First of all, I want to thank everyone who contributed to this beautiful project.

I use Ubuntu 18.04 and ros-melodic on my machine.

I did everything in the right order. However, I am having an RVIZ problem:
It says that there is no Fixed Frame [world] does not exist.
I would really appreciate if any one could help.

setting up environment variable

image
I followed the guide provided, Using ros-melodic-desktop-full, and gurobi both are working fine.
after "wstool merge .........." command I entered "wstool update" but after that no errors showed.
my workspace is in home directory but i can not find "/devel/setup.bash" in there.
so I got error
bash: /home/mrp/ws/devel/setup.bash: No such file or directory

Can you please tell me PATH_TO_YOUR_WS should appear after compiled right? or it will be in any other location?
(I searched devel/setup.bash every folder under /home/mrp/ws.)

Apart from that for the final simulation, NVIDIA GEFORCE 920M is enough?

ERROR

I have installed gurobi_9.0.0 its giving this error during installation.

Screenshot from 2022-12-05 03-39-05

An error occurred while building

Hi developer~

i tried to build the project for ground robot and an error occurs. then i tried to build for drone and got the same error

Errors     << global_mapper_ros:make /home/moyf/Workspace/ws/logs/global_mapper_ros/build.make.000.log                                                                                                     
/home/moyf/Workspace/ws/devel/.private/global_mapper_ros/lib/libglobal_mapper_ros.so:对‘global_mapper::GlobalMapper::PushPointCloud(boost::shared_ptr<pcl::PointCloud<pcl::PointXYZI> const> const&)’未定义的引用(undefined reference)
collect2: error: ld returned 1 exit status
make[2]: *** [/home/moyf/Workspace/ws/devel/.private/global_mapper_ros/lib/global_mapper_ros/global_mapper_node] Error 1
make[1]: *** [CMakeFiles/global_mapper_node.dir/all] Error 2
make[1]: *** 正在等待未完成的任务(Waiting for unfinished missions)....
make: *** [all] Error 2
cd /home/moyf/Workspace/ws/build/global_mapper_ros; catkin build --get-env global_mapper_ros | catkin env -si  /usr/bin/make --jobserver-fds=6,7 -j; cd -

I've tried this #issues-when-installing-gurobi,it fix other errors but this error remains unfixed

I'm using ROS melodic and gurobi 9.0.3

Unable to navigate drone in z axis

When we set the goal of the drone such that there is change in z-axis coordinate (say from 0,0,0 to 0,0,10). The drone does not move and the faster algorithm keeps outputting “goal reached". Does the FASTER algorithm consider the z axis?

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.