Skip to content

Commit

Permalink
Add tf2_geometry_msgs as rviz plugin dependency
Browse files Browse the repository at this point in the history
  • Loading branch information
FelipeGdM committed Dec 8, 2023
1 parent 4fe46fc commit ab9664d
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 1 deletion.
1 change: 1 addition & 0 deletions install_dependencies.sh
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@ sudo apt-get install --no-install-recommends -y \
wget \
qt5-default \
ros-$ROS_DISTRO-pcl-conversions \
ros-$ROS_DISTRO-tf2-geometry-msgs \
$ADDITIONAL_PACKAGES

pip$PYTHON_SUFFIX install --upgrade pip$PYTHON_SUFFIX
Expand Down
3 changes: 2 additions & 1 deletion rviz_carla_plugin/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@

<build_depend>qtbase5-dev</build_depend>
<depend>carla_msgs</depend>
<build_depend>tf2_geometry_msgs</build_depend>
<build_depend>nav_msgs</build_depend>
<build_depend>geometry_msgs</build_depend>
<build_depend>carla_ros_scenario_runner_types</build_depend>
Expand All @@ -27,7 +28,7 @@
<exec_depend>libqt5-core</exec_depend>
<exec_depend>libqt5-gui</exec_depend>
<exec_depend>libqt5-widgets</exec_depend>

<export>
<rviz condition="$ROS_VERSION == 1" plugin="${prefix}/plugin_description.xml"/> -->
<build_type condition="$ROS_VERSION == 1">catkin</build_type>
Expand Down

0 comments on commit ab9664d

Please sign in to comment.