Skip to content

Commit 9242bd8

Browse files
committed
Merge branch 'master' of github.com:ipa320/cob_apps
2 parents 99fc137 + 3aa58a9 commit 9242bd8

File tree

92 files changed

+2873
-1585
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

92 files changed

+2873
-1585
lines changed
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,11 @@
1+
TrajectoryPlannerROS:
2+
max_vel_x: 0.5
3+
min_vel_x: 0.1
4+
max_rotational_vel: 0.5
5+
min_in_place_rotational_vel: 0.3
6+
7+
acc_lim_th: 3.2
8+
acc_lim_x: 2.5
9+
acc_lim_y: 2.5
10+
11+
holonomic_robot: true
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,27 @@
1+
#BEGIN VOXEL STUFF
2+
#map_type: voxel
3+
map_type: costmap
4+
origin_z: 0.0
5+
z_voxels: 16
6+
z_resolution: 0.1125
7+
unknown_cost_value: 0
8+
unknown_threshold: 8
9+
mark_threshold: 0
10+
#END VOXEL STUFF
11+
12+
transform_tolerance: 0.2
13+
obstacle_range: 2.5
14+
raytrace_range: 3.0
15+
inflation_radius: 0.55
16+
17+
# BEGIN VOXEL STUFF
18+
observation_sources: laser_scan_front laser_scan_rear cloud_full_cloud laser_scan_top
19+
20+
laser_scan_front: {sensor_frame: base_laser_front_link, topic: /scan_front, data_type: LaserScan, marking: true, clearing: true}
21+
22+
laser_scan_rear: {sensor_frame: base_laser_rear_link, topic: /scan_rear, data_type: LaserScan, marking: true, clearing: true}
23+
24+
laser_scan_top: {sensor_frame: base_laser_top_link, topic: /scan_top, data_type: LaserScan, marking: true, clearing: true}
25+
26+
cloud_full_cloud: {sensor_frame: head_tof_frame, topic: /full_cloud, data_type: PointCloud, marking: true, clearing: true}
27+
# END VOXEL STUFF
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,6 @@
11
global_costmap:
22
global_frame: /map
3-
robot_base_frame: /base_footprint
3+
robot_base_frame: base_footprint
44
update_frequency: 5.0
5+
publish_frequency: 2.0
56
static_map: true
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,12 @@
1+
local_costmap:
2+
global_frame: odom_combined
3+
robot_base_frame: base_footprint
4+
update_frequency: 5.0
5+
publish_frequency: 2.0
6+
static_map: false
7+
rolling_window: true
8+
width: 6.0
9+
height: 6.0
10+
resolution: 0.025
11+
origin_x: 0.0
12+
origin_y: 0.0
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,12 @@
1+
global_costmap:
2+
global_frame: odom_combined
3+
robot_base_frame: base_footprint
4+
update_frequency: 5.0
5+
publish_frequency: 2.0
6+
static_map: false
7+
rolling_window: true
8+
width: 6.0
9+
height: 6.0
10+
resolution: 0.025
11+
origin_x: 0.0
12+
origin_y: 0.0
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,12 @@
1+
local_costmap:
2+
global_frame: odom_combined
3+
robot_base_frame: base_footprint
4+
update_frequency: 5.0
5+
publish_frequency: 2.0
6+
static_map: false
7+
rolling_window: true
8+
width: 6.0
9+
height: 6.0
10+
resolution: 0.025
11+
origin_x: 0.0
12+
origin_y: 0.0

cob_2dnav/ros/launch/2dnav.launch

+25-27
Original file line numberDiff line numberDiff line change
@@ -1,32 +1,30 @@
11
<?xml version="1.0"?>
22
<launch>
33

4-
<!-- Run the map server -->
5-
<node name="map_server" pkg="map_server" type="map_server" args="$(find cob_default_config)/envs/$(env ROBOT_ENV)/map.yaml"/>
6-
7-
<!--- Run AMCL -->
8-
<include file="$(find cob_2dnav)/ros/launch/amcl_omni.launch" />
9-
10-
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
11-
<remap from="cmd_vel" to="base_controller/command"/>
12-
<remap from="odom" to="base_odometry/odom"/>
13-
<rosparam file="$(find cob_2dnav)/ros/launch/costmap_common_params.yaml" command="load" ns="global_costmap" />
14-
<rosparam file="$(find cob_2dnav)/ros/launch/costmap_common_params.yaml" command="load" ns="local_costmap" />
15-
<rosparam file="$(find cob_2dnav)/ros/launch/local_costmap_params.yaml" command="load" />
16-
<rosparam file="$(find cob_2dnav)/ros/launch/global_costmap_params.yaml" command="load" />
17-
<rosparam file="$(find cob_2dnav)/ros/launch/base_local_planner_params.yaml" command="load" />
18-
</node>
19-
20-
<!-- Robot pose ekf -->
21-
<node pkg="robot_pose_ekf" type="robot_pose_ekf" name="robot_pose_ekf" output="screen">
22-
<param name="freq" value="30.0"/>
23-
<param name="sensor_timeout" value="1.0"/>
24-
<param name="publish_tf" value="true"/>
25-
<param name="odom_used" value="true"/>
26-
<param name="imu_used" value="true"/>
27-
<param name="vo_used" value="false"/>
28-
<remap from="odom" to="base_controller/odometry" />
29-
<remap from="imu_data" to="torso_lift_imu/data" />
30-
</node>
4+
<!-- Run the map server -->
5+
<node name="map_server" pkg="map_server" type="map_server" args="$(find cob_default_config)/envs/$(env ROBOT_ENV)/map.yaml"/>
6+
7+
<!--- Run AMCL -->
8+
<include file="$(find cob_2dnav)/ros/launch/amcl_omni.launch" />
9+
10+
<!--- Run move base -->
11+
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
12+
<remap from="cmd_vel" to="base_controller/command"/>
13+
<remap from="odom" to="base_controller/odometry"/>
14+
15+
<!--- load common configuration files -->
16+
<rosparam file="$(find cob_2dnav)/ros/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
17+
<rosparam file="$(find cob_2dnav)/ros/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
18+
19+
<!--- load global navigation specific parameters -->
20+
<rosparam file="$(find cob_2dnav)/ros/config/global/local_costmap_params.yaml" command="load" />
21+
<rosparam file="$(find cob_2dnav)/ros/config/global/global_costmap_params.yaml" command="load" />
22+
23+
<!--- load planner parameters -->
24+
<rosparam file="$(find cob_2dnav)/ros/config/base_local_planner_params.yaml" command="load" />
25+
</node>
26+
27+
<!-- Robot pose ekf -->
28+
<include file="$(find cob_2dnav)/ros/launch/robot_pose_ekf.launch" />
3129

3230
</launch>
+24
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,24 @@
1+
<?xml version="1.0"?>
2+
<launch>
3+
4+
<!--- Run move base -->
5+
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
6+
<remap from="cmd_vel" to="base_controller/command"/>
7+
<remap from="odom" to="base_controller/odometry"/>
8+
9+
<!--- load common configuration files -->
10+
<rosparam file="$(find cob_2dnav)/ros/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
11+
<rosparam file="$(find cob_2dnav)/ros/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
12+
13+
<!--- load global navigation specific parameters -->
14+
<rosparam file="$(find cob_2dnav)/ros/config/local/local_costmap_params.yaml" command="load" />
15+
<rosparam file="$(find cob_2dnav)/ros/config/local/global_costmap_params.yaml" command="load" />
16+
17+
<!--- load planner parameters -->
18+
<rosparam file="$(find cob_2dnav)/ros/config/base_local_planner_params.yaml" command="load" />
19+
</node>
20+
21+
<!-- Robot pose ekf -->
22+
<include file="$(find cob_2dnav)/ros/launch/robot_pose_ekf.launch" />
23+
24+
</launch>
+20
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,20 @@
1+
<?xml version="1.0"?>
2+
<launch>
3+
4+
<!-- dynamic map generation -->
5+
<include file="$(find cob_2dslam)/ros/launch/gmapping.launch" />
6+
7+
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
8+
<remap from="cmd_vel" to="base_controller/command"/>
9+
<remap from="odom" to="base_controller/odometry"/>
10+
<rosparam file="$(find cob_2dnav)/ros/config/base_local_planner_params.yaml" command="load" />
11+
<rosparam file="$(find cob_2dnav)/ros/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
12+
<rosparam file="$(find cob_2dnav)/ros/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
13+
<rosparam file="$(find cob_2dnav)/ros/config/global/local_costmap_params.yaml" command="load" />
14+
<rosparam file="$(find cob_2dnav)/ros/config/global/global_costmap_params.yaml" command="load" />
15+
</node>
16+
17+
<!-- Robot pose ekf -->
18+
<include file="$(find cob_2dnav)/ros/launch/robot_pose_ekf.launch" />
19+
20+
</launch>

cob_2dnav/ros/launch/base_local_planner_params.yaml

-47
This file was deleted.

cob_2dnav/ros/launch/costmap_common_params.yaml

-18
This file was deleted.

cob_2dnav/ros/launch/local_costmap_params.yaml

-8
This file was deleted.
+16
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,16 @@
1+
<?xml version="1.0"?>
2+
<launch>
3+
4+
<!-- Robot pose ekf -->
5+
<node pkg="robot_pose_ekf" type="robot_pose_ekf" name="robot_pose_ekf" output="screen">
6+
<param name="freq" value="30.0"/>
7+
<param name="sensor_timeout" value="1.0"/>
8+
<param name="publish_tf" value="true"/>
9+
<param name="odom_used" value="true"/>
10+
<param name="imu_used" value="true"/>
11+
<param name="vo_used" value="false"/>
12+
<remap from="odom" to="base_controller/odometry" />
13+
<remap from="imu_data" to="torso_lift_imu/data" />
14+
</node>
15+
16+
</launch>

cob_2dslam/manifest.xml

+1-4
Original file line numberDiff line numberDiff line change
@@ -9,10 +9,7 @@
99
<review status="unreviewed" notes=""/>
1010
<url>http://ros.org/wiki/cob_2dslam</url>
1111

12-
<depend package="cob_base"/>
13-
<depend package="cob_sick_s300"/>
14-
<depend package="cob_hokuyo"/>
1512
<depend package="gmapping"/>
16-
<depend package="cob_teleop"/>
13+
<depend package="cob_bringup"/>
1714

1815
</package>

cob_2dslam/ros/launch/2dslam.launch

+1-9
Original file line numberDiff line numberDiff line change
@@ -2,15 +2,7 @@
22
<launch>
33

44
<!-- dynamic map generation -->
5-
<node pkg="gmapping" type="slam_gmapping" name="slam_gmapping" output="screen">
6-
<remap from="scan" to="scan_front"/>
7-
<param name="maxUrange" type="int" value="8"/>
8-
<param name="xmin" type="int" value="-8"/>
9-
<param name="ymin" type="int" value="-8"/>
10-
<param name="xmax" type="int" value="8"/>
11-
<param name="ymax" type="int" value="8"/>
12-
<param name="odom_frame" type="string" value="odom_combined"/>
13-
</node>
5+
<include file="$(find cob_2dslam)/ros/launch/gmapping.launch" />
146

157
<!-- Robot pose ekf -->
168
<node pkg="robot_pose_ekf" type="robot_pose_ekf" name="robot_pose_ekf" output="screen">

cob_arm_navigation/CMakeLists.txt

+7-5
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,10 @@ set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)
1919
#uncomment if you have defined messages
2020
#rosbuild_genmsg()
2121
#uncomment if you have defined services
22-
#rosbuild_gensrv()
22+
rosbuild_gensrv()
23+
24+
# add include search paths
25+
INCLUDE_DIRECTORIES(${PROJECT_SOURCE_DIR}/include)
2326

2427
#common commands for building c++ executables and libraries
2528
#rosbuild_add_library(${PROJECT_NAME} src/example.cpp)
@@ -29,12 +32,11 @@ set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)
2932
#rosbuild_add_executable(example examples/example.cpp)
3033
#target_link_libraries(example ${PROJECT_NAME})
3134
rosbuild_add_executable(addCylinder src/addCylinder.cpp)
32-
rosbuild_add_executable(addArmObstacle src/addArmObstacle.cpp)
3335
rosbuild_add_executable(addFloor src/addFloor.cpp)
34-
rosbuild_add_executable(addURDF src/addURDF.cpp)
3536
rosbuild_add_executable(addWorld src/addWorld.cpp)
37+
rosbuild_add_executable(addObject src/addObject.cpp)
38+
rosbuild_add_executable(object_handler src/object_handler.cpp)
39+
rosbuild_add_executable(test_object_handler src/test_object_handler.cpp)
3640
rosbuild_add_executable(move_arm_joint_goal src/move_arm_joint_goal.cpp)
37-
rosbuild_add_executable(move_arm_joint_goal_prmce src/move_arm_joint_goal_prmce.cpp)
3841
rosbuild_add_executable(move_arm_simple_pose_goal src/move_arm_simple_pose_goal.cpp)
39-
rosbuild_add_executable(move_arm_simple_pose_goal_prmce src/move_arm_simple_pose_goal_prmce.cpp)
4042

0 commit comments

Comments
 (0)