A Personalized Comfort Space with Variable Shape Based on Environmental Information for Robot Navigation in Homes
This plugin takes the comfort distance, the pose, and velocity of human as inputs, and implements our comfort spaces as a layer of the costmap. The input variables are fed to the program based on ROS topic /people_features
.
The type of /people_features
is the message people_domestic_features
.
/people_domestic_features
:
std_msgs/Header header
person_domestic_features[] people
/person_domestic_features
:
string name
geometry_msgs/Point position
geometry_msgs/Point velocity
float64 alpha
The plugin outputs the comfort spaces to the costmap.
-
Compile this folder using the Catkin system of ROS.
-
Insert the following two pieces of code into the configuration file of
.yaml
corresponding tocostmap_2d
package.
- name: csce_domestic_social_layer
type: 'domestic_social_navigation_layers_csce::Personalspace'
csce_domestic_social_layer:
enabled: true
For example:
local_costmap:
plugins:
- name: obstacle_laser_layer
type: 'costmap_2d::ObstacleLayer'
- name: csce_domestic_social_layer
type: 'domestic_social_navigation_layers_csce::Personalspace'
- name: inflation_layer
type: 'costmap_2d::InflationLayer'
local_costmap:
map_type: costmap
global_frame : odom
robot_base_frame: base_footprint
update_frequency : 5.0
publish_frequency: 1.0
static_map : false
rolling_window: true
width : 4.0
height : 4.0
resolution : 0.025
robot_radius: 0.275
obstacle_laser_layer:
enabled: true
observation_sources: base_scan
combination_method: 0 # can erase static layer
base_scan:
sensor_frame: base_laser_link
data_type: LaserScan
topic: scan
expected_update_rate: 0.3
observation_persistence: 0.0
inf_is_valid: true
marking: true
clearing: true
raytrace_range: 4.0
obstacle_range: 3.0
csce_domestic_social_layer:
enabled: true
inflation_layer:
enabled : true
inflation_radius : 0.55
cost_scaling_factor: 5.0
global_costmap:
plugins:
- name: static_layer
type: 'costmap_2d::StaticLayer'
- name: obstacle_laser_layer
type: 'costmap_2d::ObstacleLayer'
- name: csce_domestic_social_layer
type: 'domestic_social_navigation_layers_csce::Personalspace'
- name: inflation_layer
type: 'costmap_2d::InflationLayer'
global_costmap:
map_type: costmap
global_frame : map
robot_base_frame: base_footprint
update_frequency : 10.0
publish_frequency: 1.0
transform_tolerance: 0.2
track_unknown_space: true
unknown_cost_value : 255
robot_radius: 0.275
static_layer:
enabled : true
map_topic: map
obstacle_laser_layer:
enabled: true
observation_sources: base_scan
combination_method: 0 # can erase static layer
base_scan:
sensor_frame: base_laser_link
data_type: LaserScan
topic: scan
expected_update_rate: 0.3
observation_persistence: 0.0
inf_is_valid: true
marking: true
clearing: true
raytrace_range: 4.0
obstacle_range: 3.0
csce_domestic_social_layer:
enabled: true
inflation_layer:
enabled : true
inflation_radius : 0.55
cost_scaling_factor: 25.0
rostopic pub /people_features dostic_social_navigation_layers_csce/people_domestic_features "header:
seq: 0
stamp:
secs: 0
nsecs: 0
frame_id: 'map'
people:
- name: '1'
position:
x: -0.924268356214
y: 0.126892251649
z: 0.0
velocity:
x: 0.8
y: 0.0
z: 0.0
alpha: 1.0"
- Send input data to plugins through detection programs, scripts or terminal commands.
- Some examples of transient navigation are shown in
./video/transient_spaces-1.mp4
. - Some examples of dynamic navigation are shown in
./video/dynamic_spaces-1.mp4
.