From 994240f2a99af681b5fd4075d7f1801933369d86 Mon Sep 17 00:00:00 2001 From: Luis Camero Date: Wed, 16 Aug 2023 16:20:51 -0400 Subject: [PATCH] Updated samples to include workspace --- clearpath_config/sample/a200/a200_default.yaml | 13 ++++++++++++- clearpath_config/sample/a200/a200_dual_laser.yaml | 13 ++++++++++++- clearpath_config/sample/a200/a200_sample.yaml | 13 ++++++++++++- clearpath_config/sample/a200/a200_velodyne.yaml | 13 ++++++++++++- clearpath_config/sample/j100/j100_default.yaml | 12 +++++++++++- clearpath_config/sample/j100/j100_dual_laser.yaml | 12 +++++++++++- clearpath_config/sample/j100/j100_sample.yaml | 12 +++++++++++- clearpath_config/sample/j100/j100_velodyne.yaml | 12 +++++++++++- 8 files changed, 92 insertions(+), 8 deletions(-) diff --git a/clearpath_config/sample/a200/a200_default.yaml b/clearpath_config/sample/a200/a200_default.yaml index 0968c87..5028995 100644 --- a/clearpath_config/sample/a200/a200_default.yaml +++ b/clearpath_config/sample/a200/a200_default.yaml @@ -12,6 +12,8 @@ system: namespace: a200_0000 domain_id: 0 rmw_implementation: rmw_fastrtps_cpp + workspaces: + - /home/administrator/micro_ros_ws/install/setup.bash platform: controller: ps4 attachments: @@ -39,7 +41,16 @@ platform: rpy: [0.0, 0.0, 0.0] extras: urdf: null - ros_parameters: {} + ros_parameters: + platform_velocity_controller: + linear.x.max_velocity": 1.0 + linear.x.min_velocity": -1.0 + linear.x.max_acceleration": 3.0 + linear.x.min_acceleration": -3.0 + angular.z.max_velocity": 2.0 + angular.z.min_velocity": -2.0 + angular.z.max_acceleration": 6.0 + angular.z.min_acceleration": -6.0 links: box: [] cylinder: [] diff --git a/clearpath_config/sample/a200/a200_dual_laser.yaml b/clearpath_config/sample/a200/a200_dual_laser.yaml index 070d63d..e4505cd 100644 --- a/clearpath_config/sample/a200/a200_dual_laser.yaml +++ b/clearpath_config/sample/a200/a200_dual_laser.yaml @@ -12,6 +12,8 @@ system: namespace: a200_0000 domain_id: 0 rmw_implementation: rmw_fastrtps_cpp + workspaces: + - /home/administrator/micro_ros_ws/install/setup.bash platform: controller: ps4 attachments: @@ -39,7 +41,16 @@ platform: rpy: [0.0, 0.0, 0.0] extras: urdf: null - ros_parameters: {} + ros_parameters: + platform_velocity_controller: + linear.x.max_velocity": 1.0 + linear.x.min_velocity": -1.0 + linear.x.max_acceleration": 3.0 + linear.x.min_acceleration": -3.0 + angular.z.max_velocity": 2.0 + angular.z.min_velocity": -2.0 + angular.z.max_acceleration": 6.0 + angular.z.min_acceleration": -6.0 links: box: [] cylinder: [] diff --git a/clearpath_config/sample/a200/a200_sample.yaml b/clearpath_config/sample/a200/a200_sample.yaml index 3f236f4..8ced995 100644 --- a/clearpath_config/sample/a200/a200_sample.yaml +++ b/clearpath_config/sample/a200/a200_sample.yaml @@ -12,6 +12,8 @@ system: namespace: a200_0000 domain_id: 0 rmw_implementation: rmw_fastrtps_cpp + workspaces: + - /home/administrator/micro_ros_ws/install/setup.bash platform: controller: ps4 attachments: @@ -39,7 +41,16 @@ platform: rpy: [0.0, 0.0, 0.0] extras: urdf: null - control: null + ros_parameters: + platform_velocity_controller: + linear.x.max_velocity": 1.0 + linear.x.min_velocity": -1.0 + linear.x.max_acceleration": 3.0 + linear.x.min_acceleration": -3.0 + angular.z.max_velocity": 2.0 + angular.z.min_velocity": -2.0 + angular.z.max_acceleration": 6.0 + angular.z.min_acceleration": -6.0 links: box: - name: user_bay_cover diff --git a/clearpath_config/sample/a200/a200_velodyne.yaml b/clearpath_config/sample/a200/a200_velodyne.yaml index 42e3193..74dcae8 100644 --- a/clearpath_config/sample/a200/a200_velodyne.yaml +++ b/clearpath_config/sample/a200/a200_velodyne.yaml @@ -12,6 +12,8 @@ system: namespace: a200_0000 domain_id: 0 rmw_implementation: rmw_fastrtps_cpp + workspaces: + - /home/administrator/micro_ros_ws/install/setup.bash platform: controller: ps4 attachments: @@ -39,7 +41,16 @@ platform: rpy: [0.0, 0.0, 0.0] extras: urdf: null - ros_parameters: {} + ros_parameters: + platform_velocity_controller: + linear.x.max_velocity": 1.0 + linear.x.min_velocity": -1.0 + linear.x.max_acceleration": 3.0 + linear.x.min_acceleration": -3.0 + angular.z.max_velocity": 2.0 + angular.z.min_velocity": -2.0 + angular.z.max_acceleration": 6.0 + angular.z.min_acceleration": -6.0 links: box: [] cylinder: [] diff --git a/clearpath_config/sample/j100/j100_default.yaml b/clearpath_config/sample/j100/j100_default.yaml index 18efec0..eaefaef 100644 --- a/clearpath_config/sample/j100/j100_default.yaml +++ b/clearpath_config/sample/j100/j100_default.yaml @@ -12,6 +12,8 @@ system: namespace: j100_0000 domain_id: 0 rmw_implementation: rmw_fastrtps_cpp + workspaces: + - /home/administrator/micro_ros_ws/install/setup.bash platform: controller: ps4 attachments: @@ -23,7 +25,15 @@ platform: model: default extras: urdf: null - ros_parameters: {} + ros_parameters: + linear.x.max_velocity": 2.0 + linear.x.min_velocity": -2.0 + linear.x.max_acceleration": 20.0 + linear.x.min_acceleration": -20.0 + angular.z.max_velocity": 4.0 + angular.z.min_velocity": -4.0 + angular.z.max_acceleration": 25.0 + angular.z.min_acceleration": -25.0 links: box: [] cylinder: [] diff --git a/clearpath_config/sample/j100/j100_dual_laser.yaml b/clearpath_config/sample/j100/j100_dual_laser.yaml index f624d2a..a4da8ae 100644 --- a/clearpath_config/sample/j100/j100_dual_laser.yaml +++ b/clearpath_config/sample/j100/j100_dual_laser.yaml @@ -12,6 +12,8 @@ system: namespace: j100_0000 domain_id: 0 rmw_implementation: rmw_fastrtps_cpp + workspaces: + - /home/administrator/micro_ros_ws/install/setup.bash platform: controller: ps4 attachments: @@ -23,7 +25,15 @@ platform: model: default extras: urdf: null - control: null + ros_parameters: + linear.x.max_velocity": 2.0 + linear.x.min_velocity": -2.0 + linear.x.max_acceleration": 20.0 + linear.x.min_acceleration": -20.0 + angular.z.max_velocity": 4.0 + angular.z.min_velocity": -4.0 + angular.z.max_acceleration": 25.0 + angular.z.min_acceleration": -25.0 links: box: [] cylinder: [] diff --git a/clearpath_config/sample/j100/j100_sample.yaml b/clearpath_config/sample/j100/j100_sample.yaml index 9231eee..8ff825f 100644 --- a/clearpath_config/sample/j100/j100_sample.yaml +++ b/clearpath_config/sample/j100/j100_sample.yaml @@ -12,6 +12,8 @@ system: namespace: j100_0000 domain_id: 0 rmw_implementation: rmw_fastrtps_cpp + workspaces: + - /home/administrator/micro_ros_ws/install/setup.bash platform: controller: ps4 attachments: @@ -23,7 +25,15 @@ platform: model: default extras: urdf: null - ros_parameters: {} + ros_parameters: + linear.x.max_velocity": 2.0 + linear.x.min_velocity": -2.0 + linear.x.max_acceleration": 20.0 + linear.x.min_acceleration": -20.0 + angular.z.max_velocity": 4.0 + angular.z.min_velocity": -4.0 + angular.z.max_acceleration": 25.0 + angular.z.min_acceleration": -25.0 links: box: [] cylinder: diff --git a/clearpath_config/sample/j100/j100_velodyne.yaml b/clearpath_config/sample/j100/j100_velodyne.yaml index 65e4ac5..81ffb79 100644 --- a/clearpath_config/sample/j100/j100_velodyne.yaml +++ b/clearpath_config/sample/j100/j100_velodyne.yaml @@ -12,6 +12,8 @@ system: namespace: j100_0000 domain_id: 0 rmw_implementation: rmw_fastrtps_cpp + workspaces: + - /home/administrator/micro_ros_ws/install/setup.bash platform: controller: ps4 attachments: @@ -23,7 +25,15 @@ platform: model: default extras: urdf: null - ros_parameters: {} + ros_parameters: + linear.x.max_velocity": 2.0 + linear.x.min_velocity": -2.0 + linear.x.max_acceleration": 20.0 + linear.x.min_acceleration": -20.0 + angular.z.max_velocity": 4.0 + angular.z.min_velocity": -4.0 + angular.z.max_acceleration": 25.0 + angular.z.min_acceleration": -25.0 links: box: [] cylinder: []