Skip to content

Commit

Permalink
hubero_bringup_gazebo_ros & gazebo - prepared actor.xacro and `…
Browse files Browse the repository at this point in the history
…spawn_actor.launch` for spawning Actors without modifying the existing world files [#59]
  • Loading branch information
rayvburn committed Sep 25, 2023
1 parent 1aa96f5 commit 153a6a2
Show file tree
Hide file tree
Showing 5 changed files with 214 additions and 6 deletions.
6 changes: 6 additions & 0 deletions hubero_bringup_gazebo_ros/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,12 @@ find_package(catkin REQUIRED COMPONENTS
catkin_package()

## Install
install(
PROGRAMS
scripts/xacro_spawner.sh
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

# ref: https://github.com/pal-robotics/tiago_robot/blob/kinetic-devel/tiago_bringup/CMakeLists.txt
foreach(dir launch maps rviz worlds)
install(DIRECTORY ${dir}/
Expand Down
22 changes: 16 additions & 6 deletions hubero_bringup_gazebo_ros/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -27,20 +27,28 @@ If all went OK, after few seconds after start you should see `move_base` log:
[ INFO] [1643660811.668211218, 8.331000000]: odom received!
```

**NOTE**: actor names defined in Gazebo `.world` must match names given to `.launch` file.

## Spawn
## Spawning an actor

The crucial question is: how to spawn an `Actor` with a `ActorPlugin` controller in a custom Gazebo world?

Since Gazebo entities are defined in `.world` file, one must add Actor definition to the Gazebo world. Actor definition consists of:
### Spawn with a `spawn_model` service

A handy `spawn_actor.launch` was prepared to spawn an actor controlled with the `HuBeRo` plugin in the Gazebo. Once the simulation is running, type:

```sh
roslaunch hubero_bringup_gazebo_ros spawn_actor.launch actor_name:=<ACTOR_UNIQUE_NAME>
```

### Spawn directly in the `.world` file

Typically, Gazebo entities are defined in a `.world` file, so one can also add the `Actor` definition directly to the Gazebo world. Actor definition consists of:

- starting pose definition,
- animation definitions,
- attached sensor relative pose and definition,
- plugin used to control Actor.
- plugin used to control the `Actor`.

Generally, one should use the exemplary worlds definitions as a reference to use actors in their custom worlds. Simply open `living_room.world` or `parking.world` and copy section that is related to a given actor:
Generally, one should use the exemplary worlds definitions as a reference to add actors to their custom worlds. To accomplish that, simply open `living_room.world` or `parking.world` and copy a section that is related to a given actor:

```xml
<actor name="actor1">
Expand All @@ -53,6 +61,8 @@ Generally, one should use the exemplary worlds definitions as a reference to use
</actor>
```

**NOTE**: actor names defined in Gazebo `.world` must match names given to the `.launch` file.

## ROS interface

Actors will not have mobility skills without connection with ROS Navigation stack. Also, Actors will not be able to receive task requests without connection to ROS topics. Use `example.launch` parameter definitions to properly define new Actor interfaces.
Expand Down
55 changes: 55 additions & 0 deletions hubero_bringup_gazebo_ros/launch/spawn_actor.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,55 @@
<?xml version="1.0"?>

<launch>
<!-- Parameters related to the spawned model -->
<arg name="actor_name" default="actor1" />
<arg name="pose_x" default="0.0" />
<arg name="pose_y" default="0.0" />
<arg name="pose_z" default="1.00" />
<arg name="pose_roll" default="1.5707" />
<arg name="pose_pitch" default="0.0" />
<arg name="pose_yaw" default="1.5707" />

<!-- Contents below are partially shared with the `example.launch` -->
<!-- Actor's map center pose relative to the world center pose -->
<arg name="tf_world_map" default="+0.00 +0.00 +0.00 +0.00 +0.00 +0.00"/>
<arg name="shared_map" default="true"/>
<arg name="map_frame" default="map"/>
<!-- Name of the frame used as a reference in simulator poses etc. usually, frame at the top of the ROS TF tree -->
<arg name="simulator_global_frame" default="world"/>

<!-- Namespace where communication channels (nodes) of simulated actors will be available -->
<arg name="main_ns" default="hubero"/>

<!-- Arbitrary map selected here -->
<arg name="map_file" default="$(find hubero_bringup_gazebo_ros)/maps/parking.yaml"/>
<arg name="map_bounds" default="[-10, 20, -10, 20]"/>


<!-- Load map & static TF -->
<group if="$(eval arg('shared_map') == true)">
<!-- Map server starts to provide a shared static map topic for all actors -->
<node name="map_server" pkg="map_server" type="map_server" args="$(arg map_file)" output="screen">
<param name="frame_id" value="$(arg map_frame)"/>
</node>
<!-- Start world-map (shared frame) static TF broadcast -->
<node name="world_map_tf_static" pkg="tf" type="static_transform_publisher" ns="$(arg main_ns)" args="$(arg tf_world_map) $(arg simulator_global_frame) $(arg map_frame) 50"/>
</group>

<!-- Run ROS interface for the HuBeRo actor operating in Gazebo simulation -->
<include file="$(find hubero_ros)/launch/actor.launch">
<arg name="actor_name" value="$(arg actor_name)"/>
<arg name="main_ns" value="$(arg main_ns)"/>
<arg name="map_file" value="$(arg map_file)"/>
<arg name="use_shared_map" value="$(arg shared_map)"/>
<arg name="map_frame" value="$(arg map_frame)"/>
<arg name="simulator_global_frame" value="$(arg simulator_global_frame)"/>
<arg name="tf_world_map" value="$(arg tf_world_map)"/>
<arg name="map_bounds" value="$(arg map_bounds)"/>
</include>

<!-- Spawn actor in the simulation -->
<node type="xacro_spawner.sh" pkg="hubero_bringup_gazebo_ros" name="actor_xacro_spawner" output="screen"
args="$(arg actor_name) $(arg pose_x) $(arg pose_y) $(arg pose_z) $(arg pose_roll) $(arg pose_pitch) $(arg pose_yaw)" />

</launch>
23 changes: 23 additions & 0 deletions hubero_bringup_gazebo_ros/scripts/xacro_spawner.sh
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
#!/usr/bin/env bash
#
# Pass xacro arguments one by one, beware of the order
actor_name="$1"
pose_x="$2"
pose_y="$3"
pose_z="$4"
pose_roll="$5"
pose_pitch="$6"
pose_yaw="$7"

# compose arguments to be passed to the xacro
XACRO_ARGS="actor_name:=${actor_name} pose_x:=${pose_x} pose_y:=${pose_y} pose_z:=${pose_z} pose_roll:=${pose_roll} pose_pitch:=${pose_pitch} pose_yaw:=${pose_yaw}"

# deletes lines containing SCRIPTDELETE phrase
SDF=$(xacro "$(rospack find hubero_gazebo)/urdf/actor.xacro" $XACRO_ARGS | sed "/SCRIPTDELETE/d")

# save sdf to file
SDF_FILE="/tmp/xacro_spawner_${actor_name}"
echo $SDF > $SDF_FILE

# spawn coords are defined in the xacro
rosrun gazebo_ros spawn_model -sdf -file $SDF_FILE -model $actor_name
114 changes: 114 additions & 0 deletions hubero_gazebo/urdf/actor.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,114 @@
<?xml version="1.0"?>
<sdf version="1.6">
<!-- NOTE: SCRIPTDELETE is placed here as it must be deleted from the resultant .xml to be properly loaded by the Gazebo -->
<SCRIPTDELETE xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- Also, namespace for ROS topics related to the actor -->
<xacro:arg name="actor_name" default="actor" />

<xacro:arg name="pose_x" default="6.30" />
<xacro:arg name="pose_y" default="2.50" />
<xacro:arg name="pose_z" default="1.00" />
<!-- NOTE: consider performing some calculations regarding the angles here -->
<xacro:arg name="pose_roll" default="1.5707" />
<xacro:arg name="pose_pitch" default="0.0" />
<xacro:arg name="pose_yaw" default="-1.5707" />

<!-- Arg->Property hack from PMB2 description -->
<xacro:property name="actor_name" value="$(arg actor_name)" />
<xacro:property name="pose_x" value="$(arg pose_x)" />
<xacro:property name="pose_y" value="$(arg pose_y)" />
<xacro:property name="pose_z" value="$(arg pose_z)" />
<xacro:property name="pose_roll" value="$(arg pose_roll)" />
<xacro:property name="pose_pitch" value="$(arg pose_pitch)" />
<xacro:property name="pose_yaw" value="$(arg pose_yaw)" />

<actor name="${actor_name}">
<pose>${pose_x} ${pose_y} ${pose_z} ${pose_roll} ${pose_pitch} ${pose_yaw}</pose>
<skin>
<filename>walk.dae</filename>
<scale>1.0</scale>
</skin>
<!-- laser sensor -->
<link name="laser_link">
<sensor type="gpu_ray" name="laser">
<!-- coordinate system info: x - side axis, y - height, z - person's nose heading -->
<pose>0 -0.8 0.55 0 -1.57 -1.57</pose>
<visualize>false</visualize>
<update_rate>10</update_rate>
<ray>
<scan>
<horizontal>
<samples>720</samples>
<resolution>1</resolution>
<min_angle>-2.170796</min_angle>
<max_angle>2.170796</max_angle>
</horizontal>
</scan>
<range>
<min>0.10</min>
<max>10.0</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<!-- Noise parameters based on published spec for Hokuyo laser
achieving "+-30mm" accuracy at range < 10m. A mean of 0.0m and
stddev of 0.01m will put 99.7% of samples within 0.03m of the true
reading. -->
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_head_hokuyo_controller" filename="libgazebo_ros_gpu_laser.so">
<topicName>/hubero/${actor_name}/receptor/laser_scan</topicName>
<frameName>${actor_name}/base_laser_link</frameName>
</plugin>
</sensor>
</link>

<animation name="walk">
<filename>walk.dae</filename>
<scale>1.000000</scale>
<interpolate_x>true</interpolate_x>
</animation>
<animation name="stand">
<filename>stand.dae</filename>
<scale>1.000000</scale>
<interpolate_x>true</interpolate_x>
</animation>
<animation name="sit_down">
<filename>sit_down.dae</filename>
<scale>1.000000</scale>
<interpolate_x>true</interpolate_x>
</animation>
<animation name="sitting">
<filename>sitting.dae</filename>
<scale>1.000000</scale>
<interpolate_x>true</interpolate_x>
</animation>
<animation name="stand_up">
<filename>stand_up.dae</filename>
<scale>1.000000</scale>
<interpolate_x>true</interpolate_x>
</animation>
<animation name="run">
<filename>run.dae</filename>
<scale>1.000000</scale>
<interpolate_x>true</interpolate_x>
</animation>
<animation name="talk_a">
<filename>talk_a.dae</filename>
<scale>1.000000</scale>
<interpolate_x>true</interpolate_x>
</animation>
<animation name="talk_b">
<filename>talk_b.dae</filename>
<scale>1.000000</scale>
<interpolate_x>true</interpolate_x>
</animation>

<plugin name="${actor_name}_plugin" filename="libhubero_gazebo_actor.so">
</plugin>
</actor>
</SCRIPTDELETE>
</sdf>

0 comments on commit 153a6a2

Please sign in to comment.