Code Monkey home page Code Monkey logo

mav_voxblox_planning's Introduction

mav_voxblox_planning_logo

MAV planning tools using voxblox as the map representation.

NOTE: THIS PACKAGE IS UNDER ACTIVE DEVELOPMENT! Things are subject to change at any time.

Table of Contents

Contents and Future Work

Included

  • Global Planning
    • RRT*, RRT Connect, BIT*, PRM... (OMPL interface) voxblox_rrt_planner
    • Planning on skeleton sparse graphs voxblox_skeleton_planner
    • Skeleton sparse graphs (topology) generation from ESDF voxblox maps voxblox_skeleton
    • Randomized benchmark on a variety of real maps mav_planning_benchmark
  • Path Smoothing (between waypoints)
    • Velocity ramp mav_path_smoothing
    • Polynomial with adding additional vertices at collisions mav_path_smoothing
    • Local polynomial optimization (Loco), unconstraining waypoints and minimizing collisions mav_path_smoothing, loco_planner
  • Local Planning -- mav_local_planner
    • Interface to MAV controller, sending timed, dynamically feasible trajectories and replanning online mav_local_planner
    • Planning in a short horizon in unknown or partially unknown spaces, using trajectory optimization in ESDFs voxblox_loco_planner
    • Path smoothing between waypoints if all waypoints are in known free space mav_path_smoothing
  • RVIZ Planning Plugin -- mav_planning_rviz
    • Allows dragging around start and goal markers, sending planning requests to global planners mav_planning_rviz
    • Allows sending goal points either directly to controller or to the local planner mav_local_planner

To Come (by end of January 2019)

  • Local Planning
    • Improved goal selection
    • Support for global and local coordinate frames
  • RVIZ Planning Plugin
    • Support for entering multiple waypoints

Papers and References

If using these, please cite:

voxblox

Helen Oleynikova, Zachary Taylor, Marius Fehr, Roland Siegwart, and Juan Nieto, “Voxblox: Incremental 3D Euclidean Signed Distance Fields for On-Board MAV Planning”. In IEEE Int. Conf. on Intelligent Robots and Systems (IROS), October 2017.
[pdf | bibtex | video | arxiv ]

loco planning

Helen Oleynikova, Michael Burri, Zachary Taylor, Juan Nieto, Roland Siegwart, and Enric Galceran, “Continuous-Time Trajectory Optimization for Online UAV Replanning”. In IEEE Int. Conf. on Intelligent Robots and Systems (IROS), October 2016.
[pdf | bibtex | video]

loco planning with voxblox

Helen Oleynikova, Zachary Taylor, Roland Siegwart, and Juan Nieto, “Safe Local Exploration for Replanning in Cluttered Unknown Environments for Micro-Aerial Vehicles”. IEEE Robotics and Automation Letters, 2018.
[pdf | bibtex | video | arxiv ]

voxblox skeleton and skeleton planning

Helen Oleynikova, Zachary Taylor, Roland Siegwart, and Juan Nieto, “Sparse 3D Topological Graphs for Micro-Aerial Vehicle Planning”. In IEEE Int. Conf. on Intelligent Robots and Systems (IROS), October 2018.
[pdf | bibtex | video | arxiv ]

Getting Started

Installation

This package is intended to be used with Ubuntu 16.04 and ROS kinetic or above. After installing ROS, install some extra dependencies, substituting kinetic for your ROS version as necessary:

sudo apt-get install ros-kinetic-cmake-modules python-wstool python-catkin-tools libyaml-cpp-dev protobuf-compiler autoconf

Then if not already done so, set up a new catkin workspace:

mkdir -p ~/catkin_ws/src
cd ~/catkin_ws
catkin init
catkin config --extend /opt/ros/kinetic
catkin config --cmake-args -DCMAKE_BUILD_TYPE=Release
catkin config --merge-devel

If using SSH keys for github (recommended):

cd ~/catkin_ws/src/
git clone [email protected]:ethz-asl/mav_voxblox_planning.git
wstool init . ./mav_voxblox_planning/install/install_ssh.rosinstall
wstool update

If not using SSH keys but using https instead:

cd ~/catkin_ws/src/
git clone https://github.com/ethz-asl/mav_voxblox_planning.git
wstool init . ./mav_voxblox_planning/install/install_https.rosinstall
wstool update

If you have already initalized wstool replace the above wstool init with wstool merge -t

Compile:

cd ~/catkin_ws/src/
catkin build mav_voxblox_planning

Download maps

We've prepared a number of maps for you to try out our planning on. The archive is 260 MB big and available here.

It contains 6 maps from 3 scenarios: machine hall (indoor), shed (mixed indoor and outdoor area), and rubble (outdoor), each with Intel Realsense D400-series scans and with grayscale stereo matching scans. Each map features 3 files: esdf, skeleton (esdf + skeleton diagram), and sparse graph, which contains just the sparse graph generated using skeletonization.

Dataset Realsense Stereo
Machine Hall machine_hall_rs machine_hall_stereo
Rubble rubble_rs rubble_stereo
Shed shed_rs shed_stereo

Try out RRT and Skeleton planning

Get the planning panel

Make sure all the packages have built successfully! Re-source your workspace (source ~/catkin_ws/devel/setup.bash) and start up rviz (rviz). In rviz, select Panels -> Add New Panel and select Planning Panel: image

Next, under Displays, add an InteractiveMarkers display with the topic /planning_markers/update: image

You should now see both a path panel and start and goal arrows. You can select Edit on either the start or the goal to drag it around as an interactive marker: image

You can also edit the numbers in the x, y, z, yaw fields manually; the markers and the numbers will update automatically to match.

Using RRT voxblox planner:

In ~/catkin_ws/src/mav_voxblox_planning/voxblox_rrt_planner/launch/rrt_saved_map.launch, open the file and replace the voxblox_path to the path of one of the esdf maps you downloaded above. Then run the file:

roslaunch voxblox_rrt_planner rrt_saved_map.launch

Note that the Fixed Frame in RVIZ should match the value for the frame_id parameter in the launch file, in this case map. Using the another value for the Fixed Frame will result in no mesh display.

In the planning panel, enter voxblox_rrt_planner as the planner name, and add a VoxbloxMesh display with the topic /voxblox_rrt_planner/mesh and a MarkerArray display with the topic /voxblox_rrt_planner/path. You can now press the "Planner Service" button to plan! In green is the RRT output path, and the other colors show different types of smoothing through these waypoints.

image

Using the Skeleton planner:

Very similar to above... Open ~/catkin_ws/src/mav_voxblox_planning/voxblox_skeleton_planner/launch/skeleton_saved_map.launch and update the paths to point to matching skeleton and sparse graph files from the maps above. Run it with:

roslaunch voxblox_skeleton_planner skeleton_saved_map.launch

In the planning panel, enter voxblox_skeleton_planner as the planner name, and add a VoxbloxMesh display with the topic /voxblox_skeleton_planner/mesh and a MarkerArray display with the topic /voxblox_skeleton_planner/path. Additionally you can add a MarkerArray with topic /voxblox_skeleton_planner/sparse_graph You can now press the "Planner Service" button to plan! Pink is the shortened path from the sparse graph, and teal is smoothed using loco through it.

image

Try out Local Planning

This demo is about using the mav_local_planner to do live replanning at 4 Hz in a simulation environment. The local planner uses loco to locally track a waypoint, or if given a list of waypoints, plan a smooth path through them.

loco_really_small

Install Rotors Simulator

Follow the installation instructions here to install Rotors Simulator, which is an MAV simulator built on top of gazebo. This will allow us to fully simulate a typical MAV, with a visual-inertial sensor mounted on it.

Install the planning pannel (if you haven't yet)

See instructions above: here.

Run the simulation

After rotors is up and running, in a new terminal, launch the firefly sim: roslaunch mav_local_planner firefly_sim.launch

A gazebo window will come up, showing something similar to this: gazebo_local_sim

You can then control the MAV using the planning panel. Enter firefly as the Namespace in the planning panel, then either type a position for the goal or edit the goal to drag it around. To send it to the local planner, press the Send Waypoint button.

The trajectory will be visualized as a visualization_msgs/MarkerArray with the topic /firefly/mav_local_planner/local_path and you can view the explored mesh as a voxblox_msgs/Mesh message with the topic /firefly/voxblox_node/mesh. The complete setup is shown below:

rviz_local_sim1

In case the MAV gets stuck, you can use Send to Controller, which will directly send the pose command to the controller -- with no collision avoidance or trajectory planning.

Try out global + local planning

Once you've explored some of the map in simulation, you can also use the global planner to plan longer paths through known space. First, start the simulation global RRT* planner (this is in addition to the firefly_sim.launch file above):

roslaunch voxblox_rrt_planner firefly_rrt.launch

Local planning only uses the goal point, but global planning requires a start point as well (as the global planner does not know the odometry of the MAV). For this, we can use the Set start to odom option in the planning panel. To do this, in the Odometry Topic field, enter ground_truth/odometry and check the Set start to odom check-box. Now the start location will automatically track the odometry of the Firefly as it moves.

Once the start and goal poses are set as you want, press Planner Service. In rviz, add a MarkerArray display with the topic /firefly/voxblox_rrt_planner/path to visualize what the planner has planned. Once you are happy with this path, press Publish Path to send it to the local planner, which should start tracking the path immediately.

rviz_global_local

Advanced

Skeletonize your own maps

TODO! Instructions coming soon. See the voxblox_skeleton/launch/skeletonize_map.launch file for reference, please make an issue if there are any questions or problems.

mav_voxblox_planning's People

Contributors

alexmillane avatar helenol avatar jaeyoung-lim avatar madratman avatar mfehr avatar rikba avatar tonirv 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  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

mav_voxblox_planning's Issues

Outdated documentation/READ.ME?

Is the update/to come of January 2019 already processed?
It looks like it has since many commits and merges have taken place already.

To Come (by end of January 2019)

Local Planning
    Improved goal selection
    Support for global and local coordinate frames
RVIZ Planning Plugin
    Support for entering multiple waypoints

Pixhawk SITL

Can this repository work with PX4 Software in the loop?

RViz Config

Dear collegues,
Please, add your's RViz config file, when run firefly_sim.launch with firefly_rrt.launch

Compilation failed

Thank you very much for sharing the awesome code!
I just sorted the dependencies, but still have gotten this error...
Please help.

Thank you in advance.
Chang

Errors     << voxblox_skeleton:make /home/chang/ws_voxblox_plan/logs/voxblox_skeleton/build.make.002.log          
/home/chang/ws_voxblox_plan/src/mav_voxblox_planning/voxblox_skeleton/src/skeleton_generator.cpp: In member function ‘void voxblox::SkeletonGenerator::generateSparseGraph()’:
/home/chang/ws_voxblox_plan/src/mav_voxblox_planning/voxblox_skeleton/src/skeleton_generator.cpp:544:3: error: ‘GlobalIndexVector’ was not declared in this scope
   GlobalIndexVector neighbors;
   ^
/home/chang/ws_voxblox_plan/src/mav_voxblox_planning/voxblox_skeleton/src/skeleton_generator.cpp:553:21: error: ‘class voxblox::NeighborTools<voxblox::SkeletonVoxel>’ has no member named ‘getNeighborsByGlobalIndex’
     neighbor_tools_.getNeighborsByGlobalIndex(
                     ^
/home/chang/ws_voxblox_plan/src/mav_voxblox_planning/voxblox_skeleton/src/skeleton_generator.cpp:554:50: error: ‘neighbors’ was not declared in this scope
         global_index, Connectivity::kTwentySix, &neighbors);
                                                  ^
/home/chang/ws_voxblox_plan/src/mav_voxblox_planning/voxblox_skeleton/src/skeleton_generator.cpp:556:40: error: unable to deduce ‘auto&&’ from ‘neighbors’
     for (const GlobalIndex& neighbor : neighbors) {
                                        ^
/home/chang/ws_voxblox_plan/src/mav_voxblox_planning/voxblox_skeleton/src/skeleton_generator.cpp:593:9: error: ‘neighbors’ was not declared in this scope
         neighbors.clear();
         ^
/home/chang/ws_voxblox_plan/src/mav_voxblox_planning/voxblox_skeleton/src/skeleton_generator.cpp:594:25: error: ‘class voxblox::NeighborTools<voxblox::SkeletonVoxel>’ has no member named ‘getNeighborsByGlobalIndex’
         neighbor_tools_.getNeighborsByGlobalIndex(
                         ^
/home/chang/ws_voxblox_plan/src/mav_voxblox_planning/voxblox_skeleton/src/skeleton_generator.cpp:596:44: error: unable to deduce ‘auto&&’ from ‘neighbors’
         for (const GlobalIndex& neighbor : neighbors) {
                                            ^
make[2]: *** [CMakeFiles/voxblox_skeleton.dir/src/skeleton_generator.cpp.o] Error 1
make[1]: *** [CMakeFiles/voxblox_skeleton.dir/all] Error 2
make: *** [all] Error 2
cd /home/chang/ws_voxblox_plan/build/voxblox_skeleton; catkin build --get-env voxblox_skeleton | catkin env -si  /usr/bin/make --jobserver-fds=6,7 -j; cd -

Exploration of an unknown space

Hello,
Not really a bug but a question.
I've installed and tested the VoxBlox mapping and exploration package and it looks amazing!
I've got a question regarding the goal selection. Is there any specific model that will allow to select goals so that a whole unknown space will be explored?
Is it within the scope of the package? And if not, do you know of any helper package that can interact with VoxBlox in order to achieve that?
Thank you

start pose occupied!

hi!
when i try to run simulation,I got an error below.

屏幕截图 2021-11-11 16:06:35

waiting for you guys help~

Interactive markers not working in local planning example

Hi,
first of all thank you for providing this nice repository.

When running the local planning, I cannot manipulate the Interactive Markers, they blink (show up and disappear) and when I finally get hold of them, there's no published messages on the "planning_markers/update" topic. There's also an error message for a very short time in the status but I cannot read it because it disappears so quickly.

There's a lot of these log messages in master.log:

[rosmaster.master][INFO] 2019-07-10 17:23:02,143: +SUB [/planning_markers/update_full] /rviz_1562770732291274234 http://camp-empty:35123/
[rosmaster.master][INFO] 2019-07-10 17:23:02,175: -SUB [/planning_markers/update_full] /rviz_1562770732291274234 http://camp-empty:35123/

If you need further information I'll happily provide it.

Update

When I start rviz everything is fine, the interactive markers are not blinking and the logs look okay too. But as soon as I click "Edit" in the planning panel, the markers start blinking and I get these errors:

[DEBUG] [1562835110.948352929, 6931.508000000]: General: Receiving messages. (Status: OK)
[DEBUG] [1562835110.948411881, 6931.508000000]: /rviz_1562835069789698854: received keep-alive #2
[DEBUG] [1562835110.974677602, 6931.538000000]: General: Receiving messages. (Status: OK)
[DEBUG] [1562835110.974756958, 6931.538000000]: /rviz_1562835069789698854: received keep-alive #2
[DEBUG] [1562835111.453612364, 6932.018000000]: General: Receiving messages. (Status: OK)
[DEBUG] [1562835111.453674356, 6932.018000000]: /rviz_1562835069789698854: received keep-alive #2
[DEBUG] [1562835111.453703297, 6932.018000000]: General: Receiving messages. (Status: OK)
[DEBUG] [1562835111.453731904, 6932.018000000]: /rviz_1562835069789698854: received keep-alive #2
[DEBUG] [1562835111.839690793, 6932.398000000]: Creating new context for set_pose
[DEBUG] [1562835111.839761363, 6932.398000000]: Publishing set_pose
[DEBUG] [1562835111.839784637, 6932.398000000]: Publishing start
[DEBUG] [1562835111.839801789, 6932.398000000]: Publishing goal
[DEBUG] [1562835111.839873499, 6932.398000000]: Publishing set_pose
[DEBUG] [1562835111.839900634, 6932.398000000]: Publishing start
[DEBUG] [1562835111.870536336, 6932.428000000]: General: Receiving messages. (Status: OK)
[DEBUG] [1562835111.870602312, 6932.428000000]: /rviz_1562835069789698854: received update #3
[DEBUG] [1562835111.870765352, 6932.428000000]: General: Receiving messages. (Status: OK)
[DEBUG] [1562835111.870808976, 6932.438000000]: /rviz_1562835069789698854: received update #4
[DEBUG] [1562835111.872976539, 6932.438000000]: Update message with seq_num=4 is ready.
[DEBUG] [1562835111.873026573, 6932.438000000]: Update message with seq_num=3 is ready.
[DEBUG] [1562835111.873055530, 6932.438000000]: /rviz_1562835069789698854: OK (Status: OK)
[DEBUG] [1562835111.873091699, 6932.438000000]: Pushing out update #3.
[DEBUG] [1562835112.001072567, 6932.558000000]: Pushing out update #4.
[DEBUG] [1562835112.045633750, 6932.608000000]: General: Receiving messages. (Status: OK)
[DEBUG] [1562835112.045697697, 6932.608000000]: /rviz_1562835069789698854: received keep-alive #2
[DEBUG] [1562835112.045722861, 6932.608000000]: Setting state of /rviz_1562835069789698854 to 2
[DEBUG] [1562835112.045742841, 6932.608000000]: /rviz_1562835069789698854: Sequence number of update is out of order. Expected: 4 Received: 2 (Status: ERROR)
[DEBUG] [1562835112.046686698, 6932.608000000]: General: Receiving messages. (Status: OK)
[DEBUG] [1562835112.046721383, 6932.608000000]: /rviz_1562835069789698854: received keep-alive #4
[DEBUG] [1562835112.462227689, 6933.028000000]: General: Receiving messages. (Status: OK)
[DEBUG] [1562835112.462308752, 6933.028000000]: /rviz_1562835069789698854: received keep-alive #2
[DEBUG] [1562835112.462356703, 6933.028000000]: /rviz_1562835069789698854: Sequence number of update is out of order. Expected: 4 Received: 2 (Status: ERROR)
[DEBUG] [1562835112.462424526, 6933.028000000]: General: Receiving messages. (Status: OK)
[DEBUG] [1562835112.462476665, 6933.028000000]: /rviz_1562835069789698854: received keep-alive #4
[DEBUG] [1562835112.974507082, 6933.538000000]: General: Receiving messages. (Status: OK)
[DEBUG] [1562835112.974565970, 6933.538000000]: /rviz_1562835069789698854: received keep-alive #2
[DEBUG] [1562835112.974591476, 6933.538000000]: /rviz_1562835069789698854: Sequence number of update is out of order. Expected: 4 Received: 2 (Status: ERROR)
[DEBUG] [1562835112.974630782, 6933.538000000]: General: Receiving messages. (Status: OK)

Can't visualize map

Hello, First of all, thank you for opening the source code.
I think this algorithm is very useful for may researches.
I'm trying to implement this algorithm, but I can't visualize map in the rviz.

image

I'm following tutorials, but I can't find TF data like above figure.
And this is my launch file.

May I ask for your help?

<launch>
 
<arg name="voxblox_path" default="/home/son/Documents/mav_voxblox_planning_maps/machine_hall/voxblox/rs_esdf_0.10.voxblox" />
 <arg name="frame_id" default="map" />


  <node name="voxblox_rrt_planner" pkg="voxblox_rrt_planner" type="voxblox_rrt_planner_node" output="screen">
    <param name="voxblox_path" value="$(arg voxblox_path)" />
    <param name="visualize" value="true" />
    <param name="robot_radius" value="0.5" />
    <param name="tsdf_voxel_size" value="0.10" />
    <param name="tsdf_voxels_per_side" value="16" />
    <param name="update_mesh_every_n_sec" value="0.0" />
    <param name="num_seconds_to_plan" value="5.0" />
    <param name="frame_id" value="$(arg frame_id)" />
    <param name="world_frame" value="$(arg frame_id)" />
    <param name="trust_approx_solution" value="true" />
    <param name="publish_traversable" value="true" />
    <param name="split_at_collisions" value="true" />
    <param name="optimize_time" value="true" />
    <param name="verbose" value="true" />
  </node>

</launch>

mav_local_planner No-obstacle Replanning

Hi Helen.

I'm using the local planner as an interface for generating timed trajectories for the MPC. I am not using any collision avoidance. When:

<param name="avoid_collisions" value="false" />

the local planner continuously sends the trajectory every replan_dt. From looking at the code, this is a mistake and the code contradicts the comment just above. Have a look here:

https://github.com/ethz-asl/mav_voxblox_planning/blob/master/mav_local_planner/src/mav_local_planner.cpp#L202

The code below this comment simply is rerun every replanning step...

voxblox_skeleton_planner/skeleton does not appear in rviz because edge point is empty

I was running the skeleton planner and everything is fine except the skeleton diagram points. First of all, they are published as pointcloud points in ROS but no actual message is passed.
I debugged further and noticed that skeleton_generator_.getSkeleton().getEdgePoints() is empty.
Then I checked void SkeletonGenerator::updateSkeletonFromLayer() and found no skeleton point is classified as either edge or vertex.
Initially I thought it is because my generated skeleton map is wrong. So I used the rs_skeleton_0.10.voxblox and found the result to be the same. So I wonder why skeleton_layer couldn't read or get the edge points from the map?

Thank you.

Problem compiling with ros melodic

Hey,
When compiling on ROS melodic, when I get to the mav_trajectory_generation package, it fails and account of yaml dependency. The terminal looks like that:

CMake Error at /home/test/catkin_ws/devel/share/catkin_simple/cmake/catkin_simple-extras.cmake:38 (find_package):
By not providing "Findyaml_cpp_catkin.cmake" in CMAKE_MODULE_PATH this
project has asked CMake to find a package configuration file provided by
"yaml_cpp_catkin", but CMake did not find one.

Could not find a package configuration file provided by "yaml_cpp_catkin"
with any of the following names:

yaml_cpp_catkinConfig.cmake
yaml_cpp_catkin-config.cmake

Add the installation prefix of "yaml_cpp_catkin" to CMAKE_PREFIX_PATH or
set "yaml_cpp_catkin_DIR" to a directory containing one of the above files.
If "yaml_cpp_catkin" provides a separate development package or SDK, be
sure it has been installed.
Call Stack (most recent call first):
CMakeLists.txt:5 (catkin_simple)

Do you have any idea whats happening?
I've installed yaml-cpp

There were some Build Errors.

Hi bro~ I run catkin build mav_voxblox_planning ,then I met some errors. And it showed as follows.


Errors << voxblox:cmake /home/ssz/catkin_ws/mav_voxblox_planning/logs/voxblox/build.cmake.000.log
CMake Error at /home/ssz/catkin_ws/mav_voxblox_planning/devel/share/catkin_simple/cmake/catkin_simple-extras.cmake:38 (find_package):
By not providing "Findprotobuf_catkin.cmake" in CMAKE_MODULE_PATH this
project has asked CMake to find a package configuration file provided by
"protobuf_catkin", but CMake did not find one.

Could not find a package configuration file provided by "protobuf_catkin"
with any of the following names:

protobuf_catkinConfig.cmake
protobuf_catkin-config.cmake

Add the installation prefix of "protobuf_catkin" to CMAKE_PREFIX_PATH or
set "protobuf_catkin_DIR" to a directory containing one of the above files.
If "protobuf_catkin" provides a separate development package or SDK, be
sure it has been installed.
Call Stack (most recent call first):
CMakeLists.txt:5 (catkin_simple)

cd /home/ssz/catkin_ws/mav_voxblox_planning/build/voxblox; catkin build --get-env voxblox | catkin env -si /usr/bin/cmake /home/ssz/catkin_ws/mav_voxblox_planning/src/voxblox/voxblox --no-warn-unused-cli -DCATKIN_DEVEL_PREFIX=/home/ssz/catkin_ws/mav_voxblox_planning/devel -DCMAKE_INSTALL_PREFIX=/home/ssz/catkin_ws/mav_voxblox_planning/install -DCMAKE_BUILD_TYPE=Release; cd -
...............................................................................
Failed << voxblox:cmake [ Exited with code 1 ]
Failed <<< voxblox [ 16.0 seconds ]
Abandoned <<< loco_planner [ Unrelated job failed ]
Abandoned <<< mav_planning_rviz [ Unrelated job failed ]
Abandoned <<< mav_path_smoothing [ Unrelated job failed ]
Abandoned <<< voxblox_rviz_plugin [ Unrelated job failed ]
Abandoned <<< voxblox_ros [ Unrelated job failed ]
Abandoned <<< voxblox_planning_common [ Unrelated job failed ]
Abandoned <<< voxblox_loco_planner [ Unrelated job failed ]
Abandoned <<< mav_local_planner [ Unrelated job failed ]
Abandoned <<< voxblox_rrt_planner [ Unrelated job failed ]
Abandoned <<< voxblox_skeleton [ Unrelated job failed ]
Abandoned <<< voxblox_skeleton_planner [ Unrelated job failed ]
Abandoned <<< mav_planning_benchmark [ Unrelated job failed ]


Warnings << mav_planning_common:make /home/ssz/catkin_ws/mav_voxblox_planning/logs/mav_planning_common/build.make.000.log

At the Last of the terminal , it showed :
Finished <<< ceres_catkin [ 1 minute and 45.4 seconds ]
[build] Summary: 16 of 29 packages succeeded.
[build] Ignored: 6 packages were skipped or are blacklisted.
[build] Warnings: 6 packages succeeded with warnings.
[build] Abandoned: 12 packages were abandoned.
[build] Failed: 1 packages failed.
[build] Runtime: 2 minutes and 16.6 seconds total.
[build] Note: Workspace packages have changed, please re-source setup files to use them.

So how can I solve this? Any suggestions? Thanks a lot.

small error issue in voxblox_skeleton

Hi, I found out the error keep comes out.

mav_voxblox_planning/voxblox_skeleton/src/io/skeleton_io.cpp:72:75: error: cannot convert ‘uint32_t* {aka unsigned int*}’ to ‘uint64_t* {aka long unsigned int*}’ for argument ‘3’ to ‘bool voxblox::utils::readProtoMsgFromStream(std::istream*, google::protobuf::Message*, uint64_t*)’

Therefore, I changed the line 69: from uint32_t tmp_byte_offset = 0; into uint64_t tmp_byte_offset = 0; and successed to build.

I share this info with the other person who has the same problem.

I apologize if I ruined the GitHub community's rule. (I don't know where to share this kind of info.)

protobuf_catkin

Hi~ there is a problem when I run the command
catkin build mav_voxblox_planning
should I install and build the 'protobuf' package? there are some details following...

` By not providing "Findprotobuf_catkin.cmake" in CMAKE_MODULE_PATH this
project has asked CMake to find a package configuration file provided by
"protobuf_catkin", but CMake did not find one.

Could not find a package configuration file provided by "protobuf_catkin"
with any of the following names:

protobuf_catkinConfig.cmake
protobuf_catkin-config.cmake

`

Build Failed

Error while building from this command: catkin build mav_voxblox_planning

Got:
make[2]: *** [CMakeFiles/mav_planning_common.dir/src/visibility_resampling.cpp.o] Error 1 make[1]: *** [CMakeFiles/mav_planning_common.dir/all] Error 2 make: *** [all] Error 2
Failed << mav_planning_common:make [ Exited with code 2 ]

Any ideas?
Thank you

voxblox_rrt_planner with estf or tsdf

Thank u for the wonderful repo, I tried to build roslaunch voxblox_rrt_planner rrt_saved_map.launch ,however got a message in this part:
Layer type of the loaded map is: esdf but the current map is: tsdf check passed? 0

setting /run_id to 530f3164-d87e-11eb-bb73-000c291b6303
process[rosout-1]: started with pid [128209]
started core service [/rosout]
process[voxblox_rrt_planner-2]: started with pid [128224]
I0629 10:04:24.996420 128224 tsdf_server.cc:575] Successfully loaded TSDF layer.
W0629 10:04:24.996757 128224 layer_inl.h:245] Voxel size of the loaded map is: 0.1 but the current map is: 0.1 check passed? 1
VPS of the loaded map is: 16 but the current map is: 16 check passed? 1
Layer type of the loaded map is: esdf but the current map is: tsdf check passed? 0
Are the maps using the same floating-point type? 1
[ INFO] [1624932265.308767681]: Size: 0.100000 VPS: 16
[ INFO] [1624932265.576534380]: Mesh Timings:
SM Timing

mesh/generate 1 00.202106 (00.202106 +- 00.000000) [00.202106,00.202106]
mesh/publish 1 00.028598 (00.028598 +- 00.000000) [00.028598,00.028598]

online map building

Hello,

My idea is the following:

  1. Launch gazebo with any environment
  2. Tell the quadrotor to explore the environment or move to a global goal while avoiding obstacles and mapping in real-time. Imagine a search and rescue scenario where the robot must go inside a buidling and completely explore.

So the goal is to:

Subscribe to camera depth map or disparity map or point cloud and explore an environment.

This is very similar to #55.

I am struggling with this. I did the followng:

  1. roslaunch mav_local_planner firefly_sim.launch", gazebo is launched.
  2. Then i enter firefly as the Namespace in the planning panel, then edit the goalTo send it to the local planner
  3. pressed the Send Waypoint button.

But no path or mesh appears.

Can i implement my idea with this library?

Understanding of the code

Excuse me, I am trying to understand the code of firefly_sim.launch, I found that "void EsdfServer::publishMap" in esdf_server.cc was called, but I can't find which function call it, and it wasn't included in a callback function either, I am very curious about it , can I get some instructions from you?

voxblox_rrt_planner

Thank u for the wonderful repo, I tried out the package and got stuck in this part

Errors     << voxblox_rrt_planner:make /home/naveen/ethz_ws/logs/voxblox_rrt_planner/build.make.001.log                                                                                                           
/home/naveen/ethz_ws/devel/.private/voxblox_rrt_planner/lib/libvoxblox_rrt_planner.so: undefined reference to `ompl::geometric::BITstar::BITstar(std::shared_ptr<ompl::base::SpaceInformation> const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&)'
/home/naveen/ethz_ws/devel/.private/voxblox_rrt_planner/lib/libvoxblox_rrt_planner.so: undefined reference to `ompl::geometric::RRTConnect::RRTConnect(std::shared_ptr<ompl::base::SpaceInformation> const&)'
/home/naveen/ethz_ws/devel/.private/voxblox_rrt_planner/lib/libvoxblox_rrt_planner.so: undefined reference to `ompl::geometric::InformedRRTstar::InformedRRTstar(std::shared_ptr<ompl::base::SpaceInformation> const&)'
/home/naveen/ethz_ws/devel/.private/voxblox_rrt_planner/lib/libvoxblox_rrt_planner.so: undefined reference to `ompl::base::PlannerData::PlannerData(std::shared_ptr<ompl::base::SpaceInformation> const&)'
/home/naveen/ethz_ws/devel/.private/voxblox_rrt_planner/lib/libvoxblox_rrt_planner.so: undefined reference to `ompl::geometric::SimpleSetup::SimpleSetup(std::shared_ptr<ompl::base::StateSpace> const&)'
/home/naveen/ethz_ws/devel/.private/voxblox_rrt_planner/lib/libvoxblox_rrt_planner.so: undefined reference to `ompl::geometric::PRM::PRM(std::shared_ptr<ompl::base::SpaceInformation> const&, bool)'
/home/naveen/ethz_ws/devel/.private/voxblox_rrt_planner/lib/libvoxblox_rrt_planner.so: undefined reference to `ompl::geometric::RRTstar::RRTstar(std::shared_ptr<ompl::base::SpaceInformation> const&)'
/home/naveen/ethz_ws/devel/.private/voxblox_rrt_planner/lib/libvoxblox_rrt_planner.so: undefined reference to `ompl::base::Planner::setProblemDefinition(std::shared_ptr<ompl::base::ProblemDefinition> const&)'
/home/naveen/ethz_ws/devel/.private/voxblox_rrt_planner/lib/libvoxblox_rrt_planner.so: undefined reference to `ompl::base::PathLengthOptimizationObjective::PathLengthOptimizationObjective(std::shared_ptr<ompl::base::SpaceInformation> const&)'
collect2: error: ld returned 1 exit status
make[2]: *** [/home/naveen/ethz_ws/devel/.private/voxblox_rrt_planner/lib/voxblox_rrt_planner/voxblox_rrt_planner_node] Error 1
make[1]: *** [CMakeFiles/voxblox_rrt_planner_node.dir/all] Error 2
make: *** [all] Error 2

I have installed ompl library
other planner like voxblox_skeleton_planner are working fine in the system except this

No pointcloud received from rotors_simulation

Running the LOCO planning as described, by installing the rotors simulator and running roslaunch mav_local_planner firefly_sim.launch. Which results in the Gazebo window showing up. However no incoming messages seem to exist on either the /firefly/pointcloud or /firefly/vi_sensor/camera_depth/depth/points topic. Further I am able to visualize the stereo camera topic directly within Gazebo. Am I missing any additional steps/procedures to get the local planning module running?

model predictive control

How hard is to couple the local planner with the controller in a Model Predictive Control Framwork using this repo?

My goal is to construct a non-linear program with smoothness cost and collision costs (like this repo does). RRT path is the initial guess, but instead of generating a state trajectory, i generate a control trajectory. How feasible is this with the current status?

Thank you.

Quadruped robot

Hello, thank you very much for making such an excellent project open source. I want to use these algorithms on legged robots. I tried to limit the planning boundary to a certain range. It turns out that this method is feasible in the same plane. I want my robot to plan up and down stairs. What do I need to do to achieve this goal?

Planner : start position occupied error in traversable region.

Greetings,
I am experiment ing with the package using the simulation environment. I am following the instructions as provided with the package.
In some of the experiments, the planner returns the error that start position is occupied. This may be more of voxblox issue but resultant map do show that robot is in traversable region . I am attaching images for reference. Voxblox correctly identifies the walls on simulation environment.
IMG_20190405_170420

Uploading IMG_20190405_170420.jpg…

IMG_20190405_162631
IMG_20190405_162843
IMG_20190405_162505
How this error could be resolved?
IMG_20190405_162603
There is a visible cavity in the view as well. If it is culprit, how it can be avoided as sensor must have seen this region?
Also, how can local planner be influenced to add intermediate waypoints in plan?

mav_local_planner failing to plan around the obstacles

Greetings,
I am trying to plan the local path in the known ESDF map in simulation. The launch file is as supplied with the package , firefly_sim.launch, is used for experimentation. The waypoint are fed using the planner panel of the RViz.

The planner was unable to plan around obstacles. Is there any crieteria defined for choosing waypoints? Is it expected by mav_local_planner that the sequence of waypoints will avoid the obstacles i.e. the straight line path between current location to the waypoint will not be through the obstacle.
Although, the associated paper "Safe Local Exploration for Replanning in Cluttered Unknown Environments for Micro-Aerial Vehicles" do mention that obstacles can be avoided by the local planner. How I can use the released code to run the exploration behaviour of the cited paper?

Thank you for your time and releasing the code.
Regards,
Nitin

Real-time cooperation with voxblox

Hi @helenol,

The skeleton works very nice and amazingly fast.
I wonder what is the standard practice to have this planning package working with voxblox in real-time?
I wanted to run it onboard a drone to dynamically replan while building the map in with voxblox online.

Is this possible in the current stage?

Kind Regards,
Chang

Resource not found: rotors_gazebo

Hi!
When I want to try local planning,I got an error below.
屏幕截图 2021-11-16 21:11:52

Should I download rotors_simulator in this workplace?
when I install rotors_simulator,I got an error.
roslaunch rotors_gazebo mav_hovering_example.launch mav_name:=firefly world_name:=basic
gazebo
what should I do?
waiting for your guys help~

what would it take to make this package support planning for ground robots ?

HI,
I am interested in ground robotics. I am able to create a maps with visual SLAM. I would like to make plans within this created map. But there should be constrains since the robot cannot move in Z axis. I am wondering whether this software will be feasible for my use-case given I do required modifications
Thank you

Couldn't call service: /voxblox_rrt_planner/plan

Greetings! I am following the "Try out RRT and Skeleton planning" tutorial and facing issue at the "Using RRT voxblox planner" part.

The RRT output path is not shown after I pressed the "Planner Service" button as mentioned. The RVIZ reported a warning Couldn't call service: /voxblox_rrt_planner/plan.

May I know how to solve this issue? Thank you!

OS: Ubuntu 20.04
ROS version: ROS Noetic

Build errors

hello, i met the issue with follow:

Errors << voxblox_rrt_planner:make /home/jinghao/workspace/mav_voxblox_planning/catkin_ws/logs/voxblox_rrt_planner/build.make.002.log
make[2]: *** No rule to make target '/opt/ros/melodic/lib/libompl.so', needed by '/home/jinghao/workspace/mav_voxblox_planning/catkin_ws/devel/lib/libvoxblox_rrt_planner.so'. Stop.
make[1]: *** [CMakeFiles/voxblox_rrt_planner.dir/all] Error 2
make: *** [all] Error 2

Any ideas?
Thank you

How to get a file like rs_esdf_0.10.voxblox?

Hi @helenol
I'm very glad to practice your magic work!
I noticed that the map file like rs_esdf_0.10.voxblox you prepared for us seems to be a bagfile from the dataset(is it?). Can you please tell me how to generate such a file?
Thank you very much!

After skeleton planner neighborhood PR, I am getting this error!?

Thank you very much for sharing the awesome code!

In member function ‘bool voxblox::SkeletonAStar::getPathInVoxels(const BlockIndex&, const VoxelIndex&, const Vector3i&, voxblox::AlignedVector<Eigen::Matrix<int, 3, 1> >*) const’:
/home/drive/voxblox_ws/src/mav_voxblox_planning/voxblox_skeleton/include/voxblox_skeleton/skeleton_planner.h:177:5: error: ‘Neighborhood’ was not declared in this scope
     Neighborhood<>::getFromBlockAndVoxelIndexAndDirection(
     ^
/home/drive/voxblox_ws/src/mav_voxblox_planning/voxblox_skeleton/include/voxblox_skeleton/skeleton_planner.h:177:18: error: expected primary-expression before ‘>’ token
     Neighborhood<>::getFromBlockAndVoxelIndexAndDirection(
                  ^
/home/drive/voxblox_ws/src/mav_voxblox_planning/voxblox_skeleton/include/voxblox_skeleton/skeleton_planner.h:177:19: error: ‘::getFromBlockAndVoxelIndexAndDirection’ has not been declared
     Neighborhood<>::getFromBlockAndVoxelIndexAndDirection(
                   ^
/home/drive/voxblox_ws/src/mav_voxblox_planning/voxblox_skeleton/include/voxblox_skeleton/skeleton_planner.h:182:18: error: expected primary-expression before ‘>’ token
     Neighborhood<>::getFromBlockAndVoxelIndex(block_index, voxel_index,
                  ^
/home/drive/voxblox_ws/src/mav_voxblox_planning/voxblox_skeleton/include/voxblox_skeleton/skeleton_planner.h:182:19: error: ‘::getFromBlockAndVoxelIndex’ has not been declared
     Neighborhood<>::getFromBlockAndVoxelIndex(block_index, voxel_index,
                   ^
/home/drive/voxblox_ws/src/mav_voxblox_planning/voxblox_skeleton/include/voxblox_skeleton/skeleton_planner.h:189:47: error: expected primary-expression before ‘>’ token
           current_voxel_offset + Neighborhood<>::kOffsets.col(i);
                                               ^
/home/drive/voxblox_ws/src/mav_voxblox_planning/voxblox_skeleton/include/voxblox_skeleton/skeleton_planner.h:189:48: error: ‘::kOffsets’ has not been declared
           current_voxel_offset + Neighborhood<>::kOffsets.col(i);
                                                ^
/home/drive/voxblox_ws/src/mav_voxblox_planning/voxblox_skeleton/include/voxblox_skeleton/skeleton_planner.h:204:60: error: expected primary-expression before ‘>’ token
           g_score_map[current_voxel_offset] + Neighborhood<>::kDistances(i);

and so on!

Add constraints to force motion planners output paths on a same plane?

Hi @helenol ,
Thank you so much for open-source the whole pipeline :)
I have been playing with it and the results of mapping and planning are incredible :).
I would like to ask if it is possible to force motion planners output (initial, smoothed) paths on the same (x,y) plane, e.g z = const?
The reason I ask is that for my use case, I don't want my robot go through windows, which are considered traversable inside voxblox. Please have a look at my map. The RRT* path has vertices at different z values and I guess all smoothed paths will try to approximate that as well?
ask
So I guess if I can somehow force the planners to search paths only on a (x,y) plane, I might be able to avoid "elevated" paths.
I'd appreciate if you could give me hints on how I can do this.
Thanks again!

Randomized positions are occupied

I have a puzzle about the "global_planning_benchmark":The randomized start and goal position may be occupied. However, they are successfully selected from the generation proccess, and fullfill the distance function of esdf_server_. I really have no idea about this,would you mind giving some reasons? Thank you!

Build error: voxblox_skeleton/src/io/skeleton_io.cpp

When building the package, this strange error appears. There seems to be something wrong with the code, but I'm not sure.

/home/giuseppe/catkin_ws_airMPL_Simulator/src/mav_voxblox_planning/voxblox_skeleton/src/io/skeleton_io.cpp: In function ‘bool voxblox::io::loadSparseSkeletonGraphFromFile(const string&, voxblox::SparseSkeletonGraph*)’:
/home/giuseppe/catkin_ws_airMPL_Simulator/src/mav_voxblox_planning/voxblox_skeleton/src/io/skeleton_io.cpp:72:75: error: cannot convert ‘uint32_t* {aka unsigned int*}’ to ‘uint64_t* {aka long unsigned int*}’ for argument ‘3’ to ‘bool voxblox::utils::readProtoMsgFromStream(std::fstream*, google::protobuf::Message*, uint64_t*)’
   if (!utils::readProtoMsgFromStream(&proto_file, &proto, &tmp_byte_offset)) {
                                                                           ^
make[2]: *** [CMakeFiles/voxblox_skeleton.dir/src/io/skeleton_io.cpp.o] Error 1
make[1]: *** [CMakeFiles/voxblox_skeleton.dir/all] Error 2

build error and warning

Hey, my friends. I've cloned all code files correctly, and when i started to build , it appeared an error below:


Errors << nlopt:make /root/Desktop/catkin_ws/logs/nlopt/build.make.000.log
--2020-02-12 13:56:50-- https://github.com/ethz-asl/thirdparty_library_binaries/raw/master/nlopt-2.4.2.tar.gz
Resolving github.com (github.com)... 52.74.223.119
Connecting to github.com (github.com)|52.74.223.119|:443... connected.
HTTP request sent, awaiting response... 302 Found
Location: https://raw.githubusercontent.com/ethz-asl/thirdparty_library_binaries/master/nlopt-2.4.2.tar.gz [following]
--2020-02-12 13:56:51-- https://raw.githubusercontent.com/ethz-asl/thirdparty_library_binaries/master/nlopt-2.4.2.tar.gz
Resolving raw.githubusercontent.com (raw.githubusercontent.com)... 151.101.228.133
Connecting to raw.githubusercontent.com (raw.githubusercontent.com)|151.101.228.133|:443... failed: Connection refused.
make[2]: *** [nlopt_src-prefix/src/nlopt_src-stamp/nlopt_src-download] Error 4
make[1]: *** [CMakeFiles/nlopt_src.dir/all] Error 2
make: *** [all] Error 2
cd /root/Desktop/catkin_ws/build/nlopt; catkin build --get-env nlopt | catkin env -si /usr/bin/make --jobserver-fds=6,7 -j; cd -
.............................................................................................
Failed << nlopt:make [ Exited with code 2 ]
Failed <<< nlopt [ 3.1 seconds ]
Abandoned <<< eigen_catkin [ Unrelated job failed ]
Abandoned <<< gflags_catkin [ Unrelated job failed ]
Abandoned <<< voxblox_msgs [ Unrelated job failed ]
Abandoned <<< mav_planning_msgs [ Unrelated job failed ]
Abandoned <<< glog_catkin [ Unrelated job failed ]
Abandoned <<< ceres_catkin [ Unrelated job failed ]
Abandoned <<< eigen_checks [ Unrelated job failed ]
Abandoned <<< mav_visualization [ Unrelated job failed ]
Abandoned <<< minkindr [ Unrelated job failed ]
Abandoned <<< minkindr_conversions [ Unrelated job failed ]
Abandoned <<< mav_trajectory_generation [ Unrelated job failed ]
Abandoned <<< loco_planner [ Unrelated job failed ]
Abandoned <<< mav_planning_common [ Unrelated job failed ]
Abandoned <<< mav_planning_rviz [ Unrelated job failed ]
Abandoned <<< mav_trajectory_generation_ros [ Unrelated job failed ]
Abandoned <<< mav_path_smoothing [ Unrelated job failed ]
Abandoned <<< voxblox [ Unrelated job failed ]
Abandoned <<< voxblox_rviz_plugin [ Unrelated job failed ]
Abandoned <<< voxblox_ros [ Unrelated job failed ]
Abandoned <<< voxblox_planning_common [ Unrelated job failed ]
Abandoned <<< voxblox_loco_planner [ Unrelated job failed ]
Abandoned <<< mav_local_planner [ Unrelated job failed ]
Abandoned <<< voxblox_rrt_planner [ Unrelated job failed ]
Abandoned <<< voxblox_skeleton [ Unrelated job failed ]
Abandoned <<< voxblox_skeleton_planner [ Unrelated job failed ]
Abandoned <<< mav_planning_benchmark [ Unrelated job failed ]
[build] Summary: 2 of 29 packages succeeded.
[build] Ignored: 6 packages were skipped or are blacklisted.
[build] Warnings: None.
[build] Abandoned: 26 packages were abandoned.
[build] Failed: 1 packages failed.
[build] Runtime: 18.5 seconds total.
[build] Note: Workspace packages have changed, please re-source setup files to use them.

after i re-sourced set up files and rebuild, it threw warnings like:


Warnings << nlopt:make /root/Desktop/catkin_ws/logs/nlopt/build.make.001.log
--2020-02-12 13:57:56-- https://github.com/ethz-asl/thirdparty_library_binaries/raw/master/nlopt-2.4.2.tar.gz
Resolving github.com (github.com)... 13.250.177.223
Connecting to github.com (github.com)|13.250.177.223|:443... connected.
HTTP request sent, awaiting response... 302 Found
Location: https://raw.githubusercontent.com/ethz-asl/thirdparty_library_binaries/master/nlopt-2.4.2.tar.gz [following]
--2020-02-12 13:57:57-- https://raw.githubusercontent.com/ethz-asl/thirdparty_library_binaries/master/nlopt-2.4.2.tar.gz
Resolving raw.githubusercontent.com (raw.githubusercontent.com)... 151.101.108.133
Connecting to raw.githubusercontent.com (raw.githubusercontent.com)|151.101.108.133|:443... connected.
HTTP request sent, awaiting response... 200 OK
Length: 2361992 (2.3M) [application/octet-stream]
Saving to: ‘nlopt-2.4.2.tar.gz’

nlopt-2.4.2.tar.gz 100%[===================>] 2.25M 24.1KB/s in 3m 58s

2020-02-12 14:01:58 (9.70 KB/s) - ‘nlopt-2.4.2.tar.gz’ saved [2361992/2361992]

configure: WARNING: Python and Guile wrappers require --enable-shared; disabling
configure: WARNING: can't find mkoctfile: won't be able to compile GNU Octave plugin
make[3]: warning: jobserver unavailable: using -j1. Add '+' to parent make rule.
ar: u' modifier ignored since D' is the default (see U') ar: u' modifier ignored since D' is the default (see U')
……

i want to know why this happen and how to solve this problem, thanks!

mav_local_planner simulate test.

Thanks for sharing such great work to us.
I have a question about mav_local_planner simulation.
I followed your introduction to test the mav_local_planner.
After rotors are up and running, in a new terminal, I launched the firefly sim
but I got nothing likes these below:

... logging to /home/zxp/.ros/log/630ec810-4b43-11e9-894b-f43909319a96/roslaunch-zxp-mint-18561.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.

xacro: Traditional processing is deprecated. Switch to --inorder processing!
To check for compatibility of your document, use option --check-order.
For more infos, see http://wiki.ros.org/xacro#Processing_Order
redefining global property: pi
when processing file: /home/zxp/catkin_map/src/rotors_simulator/rotors_description/urdf/mav_with_vi_sensor.gazebo
xacro.py is deprecated; please use xacro instead
Traceback (most recent call last):
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/init.py", line 306, in main
p.start()
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/parent.py", line 268, in start
self._start_infrastructure()
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/parent.py", line 217, in _start_infrastructure
self._load_config()
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/parent.py", line 132, in _load_config
roslaunch_strs=self.roslaunch_strs, verbose=self.verbose)
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/config.py", line 451, in load_config_default
loader.load(f, config, verbose=verbose)
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/xmlloader.py", line 749, in load
self._load_launch(launch, ros_config, is_core=core, filename=filename, argv=argv, verbose=verbose)
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/xmlloader.py", line 721, in _load_launch
self._recurse_load(ros_config, launch.childNodes, self.root_context, None, is_core, verbose)
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/xmlloader.py", line 655, in _recurse_load
default_machine, is_core, verbose)
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/xmlloader.py", line 657, in _recurse_load
n = self._node_tag(tag, context, ros_config, default_machine, verbose=verbose)
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/xmlloader.py", line 95, in call
return f(*args, **kwds)
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/xmlloader.py", line 410, in _node_tag
self._rosparam_tag(t, param_ns, ros_config, verbose=verbose)
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/xmlloader.py", line 95, in call
return f(*args, **kwds)
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/xmlloader.py", line 228, in _rosparam_tag
cmd, ns, file, param, subst_value = self.opt_attrs(tag, context, (XmlLoader.ROSPARAM_OPT_ATTRS))
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/xmlloader.py", line 202, in opt_attrs
return [self.resolve_args(tag_value(tag,a), context) for a in attrs]
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/xmlloader.py", line 183, in resolve_args
return substitution_args.resolve_args(args, context=context.resolve_dict, resolve_anon=self.resolve_anon)
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/substitution_args.py", line 370, in resolve_args
resolved = _resolve_args(resolved, context, resolve_anon, commands)
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/substitution_args.py", line 383, in _resolve_args
resolved = commands[command](resolved, a, args, context)
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/substitution_args.py", line 151, in _find
source_path_to_packages=source_path_to_packages)
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/substitution_args.py", line 197, in _find_executable
full_path = _get_executable_path(rp.get_path(args[0]), path)
File "/usr/lib/python2.7/dist-packages/rospkg/rospack.py", line 203, in get_path
raise ResourceNotFound(name, ros_paths=self._ros_paths)
ResourceNotFound: mav_nonlinear_mpc
ROS path [0]=/opt/ros/kinetic/share/ros
ROS path [1]=/home/zxp/catkin_map/src/catkin_simple
ROS path [2]=/home/zxp/catkin_map/src/eigen_catkin
ROS path [3]=/home/zxp/catkin_map/src/gflags_catkin
ROS path [4]=/home/zxp/catkin_map/src/glog_catkin
ROS path [5]=/home/zxp/catkin_map/src/ceres_catkin
ROS path [6]=/home/zxp/catkin_map/src/eigen_checks
ROS path [7]=/home/zxp/catkin_map/src/mav_comm/mav_comm
ROS path [8]=/home/zxp/catkin_map/src/mav_comm/mav_msgs
ROS path [9]=/home/zxp/catkin_map/src/mav_voxblox_planning/mav_planning_common
ROS path [10]=/home/zxp/catkin_map/src/mav_comm/mav_planning_msgs
ROS path [11]=/home/zxp/catkin_map/src/mav_trajectory_generation/mav_visualization
ROS path [12]=/home/zxp/catkin_map/src/mav_voxblox_planning/mav_planning_rviz
ROS path [13]=/home/zxp/catkin_map/src/mav_voxblox_planning/mav_voxblox_planning
ROS path [14]=/home/zxp/catkin_map/src/mavlink
ROS path [15]=/home/zxp/catkin_map/src/mavros/libmavconn
ROS path [16]=/home/zxp/catkin_map/src/mavros/mavros_msgs
ROS path [17]=/home/zxp/catkin_map/src/mavros/mavros
ROS path [18]=/home/zxp/catkin_map/src/mavros/mavros_extras
ROS path [19]=/home/zxp/catkin_map/src/minkindr/minkindr
ROS path [20]=/home/zxp/catkin_map/src/minkindr_ros/minkindr_conversions
ROS path [21]=/home/zxp/catkin_map/src/nlopt
ROS path [22]=/home/zxp/catkin_map/src/mav_trajectory_generation/mav_trajectory_generation
ROS path [23]=/home/zxp/catkin_map/src/mav_voxblox_planning/loco_planner
ROS path [24]=/home/zxp/catkin_map/src/mav_trajectory_generation/mav_trajectory_generation_ros
ROS path [25]=/home/zxp/catkin_map/src/mav_voxblox_planning/mav_path_smoothing
ROS path [26]=/home/zxp/catkin_map/src/rotors_simulator/rotors_comm
ROS path [27]=/home/zxp/catkin_map/src/rotors_simulator/rotors_control
ROS path [28]=/home/zxp/catkin_map/src/rotors_simulator/rotors_description
ROS path [29]=/home/zxp/catkin_map/src/rotors_simulator/rotors_evaluation
ROS path [30]=/home/zxp/catkin_map/src/rotors_simulator/rotors_gazebo_plugins
ROS path [31]=/home/zxp/catkin_map/src/rotors_simulator/rotors_gazebo
ROS path [32]=/home/zxp/catkin_map/src/rotors_simulator/rotors_hil_interface
ROS path [33]=/home/zxp/catkin_map/src/rotors_simulator/rotors_joy_interface
ROS path [34]=/home/zxp/catkin_map/src/rotors_simulator/rotors_simulator
ROS path [35]=/home/zxp/catkin_map/src/rotors_simulator/rqt_rotors
ROS path [36]=/home/zxp/catkin_map/src/mavros/test_mavros
ROS path [37]=/home/zxp/catkin_map/src/voxblox/voxblox
ROS path [38]=/home/zxp/catkin_map/src/voxblox/voxblox_msgs
ROS path [39]=/home/zxp/catkin_map/src/voxblox/voxblox_rviz_plugin
ROS path [40]=/home/zxp/catkin_map/src/voxblox/voxblox_ros
ROS path [41]=/home/zxp/catkin_map/src/mav_voxblox_planning/voxblox_loco_planner
ROS path [42]=/home/zxp/catkin_map/src/mav_voxblox_planning/mav_local_planner
ROS path [43]=/home/zxp/catkin_map/src/mav_voxblox_planning/voxblox_rrt_planner
ROS path [44]=/home/zxp/catkin_map/src/mav_voxblox_planning/voxblox_skeleton
ROS path [45]=/home/zxp/catkin_map/src/mav_voxblox_planning/voxblox_skeleton_planner
ROS path [46]=/home/zxp/catkin_map/src/mav_voxblox_planning/mav_planning_benchmark
ROS path [47]=/opt/ros/kinetic/share

It seems like they can't find the mav_nonlinear_mpc.
I saw this in your other project and I have not seen the introduction motioned about it.
Do I miss some steps?
Do I need to install the mav_control_rw project(which include the mav_nonlinear_mpc, mav_linear_mpc, and other codes.) in my workspace first?
Here is the workspace on my computer.
image

Can not find and add files in in rviz panal !!!

@helenol Thanks for your respond. I solved that problem by lunching roscore in one terminal and rviz in another terminal. But still have a problem, I cant do the following:

In rviz, select Panels -> Add New Panel and select Planning Panel:
I just have the following choices
-rviz
-rviz_plugin_tutorials

I can't find other files as you mentioned in your post

IMG_20190417_204538
IMG_20190417_204514

ROS Noetic

I am trying to install this repo on ROS Noetic and its give lot of error while building, does this work in Noetic?

mav_local_planner, LOCO and waypoint list

When sending a rather large waypoint mission to mav_local_planner with "loco" for smoothing, LOCO resamples the mission to a small number of waypoints which is not really desired.

[ INFO] [1550915111.929329675, 15.860000000]: [Mav Local Planner] Got a list of waypoints, 1437 long!
Segment times: 25.4723 18.6638 24.629 31.6325 19.1197 

Can LOCO process a larger mission?

rviz_screenshot_2019_02_23-10_12_41

@baschuuuu

Problem while building?

Errors << ceres_catkin:make /home/mechali_omar/catkin_ws/logs/ceres_catkin/build.make.000.log
Cloning into 'ceres_src'...
fatal: unable to access 'https://ceres-solver.googlesource.com/ceres-solver/': Failed to connect to ceres-solver.googlesource.com port 443: Connection timed out
Cloning into 'ceres_src'...
fatal: unable to access 'https://ceres-solver.googlesource.com/ceres-solver/': Failed to connect to ceres-solver.googlesource.com port 443: Connection timed out
Cloning into 'ceres_src'...
fatal: unable to access 'https://ceres-solver.googlesource.com/ceres-solver/': Failed to connect to ceres-solver.googlesource.com port 443: Connection timed out
CMake Error at /home/mechali_omar/catkin_ws/build/ceres_catkin/ceres_src-prefix/tmp/ceres_src-gitclone.cmake:40 (message):
Failed to clone repository:
'https://ceres-solver.googlesource.com/ceres-solver'

RRT planner not able to plan for goal that is not scaned.

Hi,

I try to run the firefly simulation with local and global planning with rrt. But I found that the RRT planner is not able to plan for goal that is not scaned. For example, I'm using the goal position 5.5, 0, 1 with yaw=0. And the start position is set at odometry and it is 0,0,1 with yaw=0. When I start the planner service, it shows that the goal position is occupied. After some debugging time, I figure out that the getMapDistance function is always returning 0. And this value is generated by voxblox. Do you guys have any ideas on how can I make the planner be able to handle the area that is not scaned? Is it possible to combine the local planner and the rrt planner in this case?

Thanks a lot.

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.