Add new params, video and use_sim_time param

main
charlielito 2021-08-09 20:49:18 -07:00
parent 5be0a8a328
commit 4614dddebe
4 changed files with 41 additions and 7 deletions

View File

@ -4,15 +4,14 @@ ROS2 package port for (not yet multi) robot exploration of [m-explore](https://g
### TB3 ### TB3
https://user-images.githubusercontent.com/8033598/127044265-f59ee9d1-93c6-4b73-b022-467eeb671d2a.mp4 https://user-images.githubusercontent.com/8033598/128805356-be90a880-16c6-4fc9-8f54-e3302873dc8c.mp4
### On a JetBot with realsense cameras
https://user-images.githubusercontent.com/18732666/128493567-6841dde0-2250-4d81-9bcb-8b216e0fb34d.mp4 https://user-images.githubusercontent.com/18732666/128493567-6841dde0-2250-4d81-9bcb-8b216e0fb34d.mp4
Installing Installing
---------- ----------
@ -32,6 +31,31 @@ To run with a params file just run it with
ros2 run explore_lite explore --ros-args --params-file <path_to_ros_ws>/m-explore/explore/config/params.yaml ros2 run explore_lite explore --ros-args --params-file <path_to_ros_ws>/m-explore/explore/config/params.yaml
``` ```
### Running the demo with TB3
Install nav2 and tb3 simulation. You can follow the [tutorial](https://navigation.ros.org/getting_started/index.html#installation).
Then just run the nav2 stack with slam:
```
ros2 launch nav2_bringup tb3_simulation_launch.py slam:=true
```
And run this package with
```
ros2 launch explore_lite explore.launch.py
```
#### TB3 troubleshooting
If you have trouble with TB3 in simulation like we did, add this extra steps for configuring it.
```
source /opt/ros/${ROS_DISTRO}/setup.bash
export TURTLEBOT3_MODEL=waffle
sudo rm -rf /opt/ros/${ROS_DISTRO}/share/turtlebot3_simulations
sudo git clone https://github.com/ROBOTIS-GIT/turtlebot3_simulations /opt/ros/${ROS_DISTRO}/share/turtlebot3_simulations
export GAZEBO_MODEL_PATH=$GAZEBO_MODEL_PATH:/opt/ros/${ROS_DISTRO}/share/turtlebot3_simulations/turtlebot3_gazebo/models
```
Then you'll be able to run it.
WIKI WIKI
---- ----
No wiki yet. No wiki yet.

View File

@ -4,7 +4,7 @@ explore_node:
costmap_topic: map costmap_topic: map
costmap_updates_topic: map_updates costmap_updates_topic: map_updates
visualize: true visualize: true
planner_frequency: 0.33 planner_frequency: 0.25
progress_timeout: 30.0 progress_timeout: 30.0
potential_scale: 3.0 potential_scale: 3.0
orientation_scale: 0.0 orientation_scale: 0.0

View File

@ -4,7 +4,7 @@ explore_node:
costmap_topic: /global_costmap/costmap costmap_topic: /global_costmap/costmap
costmap_updates_topic: /global_costmap/costmap_updates costmap_updates_topic: /global_costmap/costmap_updates
visualize: true visualize: true
planner_frequency: 0.33 planner_frequency: 0.25
progress_timeout: 30.0 progress_timeout: 30.0
potential_scale: 3.0 potential_scale: 3.0
orientation_scale: 0.0 orientation_scale: 0.0

View File

@ -1,21 +1,31 @@
import os import os
from ament_index_python.packages import get_package_share_directory from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch_ros.actions import Node from launch_ros.actions import Node
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
def generate_launch_description(): def generate_launch_description():
ld = LaunchDescription() ld = LaunchDescription()
config = os.path.join( config = os.path.join(
get_package_share_directory("explore_lite"), "config", "params.yaml" get_package_share_directory("explore_lite"), "config", "params.yaml"
) )
use_sim_time = LaunchConfiguration("use_sim_time")
declare_use_sim_time_argument = DeclareLaunchArgument(
"use_sim_time", default_value="true", description="Use simulation/Gazebo clock"
)
node = Node( node = Node(
package="explore_lite", package="explore_lite",
name="explore_node", name="explore_node",
executable="explore", executable="explore",
parameters=[config], parameters=[config, {"use_sim_time": use_sim_time}],
output="screen", output="screen",
) )
ld.add_action(declare_use_sim_time_argument)
ld.add_action(node) ld.add_action(node)
return ld return ld