-
Notifications
You must be signed in to change notification settings - Fork 4
Description
Hello, I have configured Box, Sphere, and Cylinder shapes respectively and maximized both scale and padding parameters. However, the '/collision_shapes' function fails to completely filter out the robotic arm's body.
The parameter configuration file I used is self_filter.yaml, and the launch file is self_filter.launch.py.
self_filter.yaml:
`
self_filter:
ros__parameters:
# sensor_frame: "rslidar"
# sensor_frame: "base_link"
# sensor_frame: "camera_depth_optical_frame"
sensor_frame: "camera_color_optical_frame"
# For spheres (single scale & padding)
default_sphere_scale: 1.0
default_sphere_padding: 0.005
# For boxes (x,y,z scale & padding)
default_box_scale: [1.0, 1.0, 1.0]
default_box_padding: [0.02, 0.02, 0.02]
# For cylinders (radial scale, vertical scale, radial padding, vertical padding)
default_cylinder_scale: [1.0, 1.0]
default_cylinder_padding: [0.03, 0.03]
keep_organized: false
zero_for_removed_points: false
invert: false
min_sensor_dist: 0.0 # Minimum distance from sensor to avoid self-collision
self_see_links:
names:
- base_link
- shoulder_link
- upperarm_link
- forearm_link
- wrist1_link
- wrist2_link
- wrist3_link
base_link:
box_scale: [1.0, 1.0, 1.0]
box_padding: [0.5, 0.5, 0.5]
shoulder_link:
box_scale: [1.0, 1.0, 1.0]
box_padding: [0.5, 0.5, 0.5]
upperarm_link:
box_scale: [1.0, 1.0, 1.0]
box_padding: [0.5, 0.5, 0.5]
forearm_link:
# shape_type: box
shape_type: "mesh"
box_scale: [1.0, 1.0, 1.0]
box_padding: [0.5, 0.5, 0.5]
wrist1_link:
box_scale: [1.0, 1.0, 1.0]
box_padding: [0.5, 0.5, 0.5]
wrist2_link:
box_scale: [1.5, 1.5, 1.5]
box_padding: [0.5, 0.5, 0.5]
wrist3_link:
box_scale: [0.2, 0.1, 0.2]
box_padding: [0.05, 0.05, 0.1]
self_filter.launch.py:
self_filter.launch.py
import os
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, LogInfo
from launch.substitutions import LaunchConfiguration, PythonExpression
from launch_ros.actions import Node
from launch_ros.parameter_descriptions import ParameterValue
from ament_index_python.packages import get_package_share_directory
import xacro
import re
def remove_comments(text):
pattern = r''
return re.sub(pattern, '', text, flags=re.DOTALL)
def generate_launch_description():
package_name1 = 'fairino_description'
# package_name1 = 'fairino'
package_dir1 = get_package_share_directory(package_name1)
package_name2 = 'fr_motion_control'
package_dir2 = get_package_share_directory(package_name2)
default_filter_config = os.path.join(package_dir2, 'params', 'self_filter.yaml')
# default_urdf_path = os.path.join(package_dir1, 'urdf', 'integration.xacro')
default_urdf_path = os.path.join(package_dir1, 'urdf', 'fairino10_v6.urdf')
xacro_file = default_urdf_path
doc = xacro.parse(open(xacro_file))
xacro.process_doc(doc)
robot_description_content = doc.toxml()
description_name_arg = DeclareLaunchArgument(
'description_name',
default_value='/robot_description'
)
zero_for_removed_points_arg = DeclareLaunchArgument(
'zero_for_removed_points',
default_value='true'
)
lidar_sensor_type_arg = DeclareLaunchArgument(
'lidar_sensor_type',
default_value='0'
)
in_pointcloud_topic_arg = DeclareLaunchArgument(
'in_pointcloud_topic',
# default_value='/rslidar_points'
default_value='/camera/depth/points'
# default_value='/obstacle_cloud'
)
out_pointcloud_topic_arg = DeclareLaunchArgument(
'out_pointcloud_topic',
default_value='/velodyne_points_out'
# default_value='/self_filter/filtered_points'
)
robot_description_arg = DeclareLaunchArgument(
'robot_description',
default_value=robot_description_content
)
filter_config_arg = DeclareLaunchArgument(
'filter_config',
default_value=default_filter_config
)
# Declare use_sim_time argument
# use_sim_time_arg = DeclareLaunchArgument(
# 'use_sim_time',
# default_value='true', # Keep default as true for standalone use
# description='Use simulation (Gazebo) clock if true'
# )
# Create a log action to print the config
log_config = LogInfo(msg=LaunchConfiguration('filter_config'))
self_filter_node = Node(
package='robot_self_filter',
executable='self_filter',
name='self_filter',
output='screen',
parameters=[
LaunchConfiguration('filter_config'), # loads the YAML file
{
'lidar_sensor_type': LaunchConfiguration('lidar_sensor_type'),
'robot_description': ParameterValue(
LaunchConfiguration('robot_description'),
value_type=str
),
'zero_for_removed_points': LaunchConfiguration('zero_for_removed_points'),
'use_sim_time': True
# 'use_sim_time': LaunchConfiguration('use_sim_time') # Use the launch argument
}
],
remappings=[
('/robot_description', LaunchConfiguration('description_name')),
('/cloud_in', LaunchConfiguration('in_pointcloud_topic')),
('/cloud_out', LaunchConfiguration('out_pointcloud_topic')),
],
)
return LaunchDescription([
description_name_arg,
zero_for_removed_points_arg,
lidar_sensor_type_arg,
in_pointcloud_topic_arg,
out_pointcloud_topic_arg,
robot_description_arg,
filter_config_arg,
log_config,
# use_sim_time_arg, # Add to launch description
self_filter_node,
# debug_urdf
])
`
Could you please explain the specific reason for this issue?