紧急通知:禁止一切关于政治&VPN翻墙等话题,发现相关帖子会立马删除封号
小鱼 ROS 2 新书上线!点击链接查看, 新书配套视频点击链接查看。
提问前必看的发帖注意事项—— 提问前必看!不符合要求的问题拒绝回答!!
社区使用指南—如何添加标签修改密码
小鱼 ROS 2 新书上线!点击链接查看, 新书配套视频点击链接查看。
提问前必看的发帖注意事项—— 提问前必看!不符合要求的问题拒绝回答!!
社区使用指南—如何添加标签修改密码
moveit能控制rivz做路径规划但是不能控制gazebo
-
在ros2中通过moveit控制机械臂做路径规划时,通过launch文件先启动gazebo,在通过moveit生成的 demo.launch.py启动rviz,当moveit做路径规划时,rviz能够正常移动,但是gazebo有些时候不能正常移动(在没有修改任何代码的情况下有些时候启动的时候可以,有些时候启动不可以),下图为启动rviz时的终端图片,没有修改任何代码,两次启动的情况都不一样
我通过网上查询,怀疑是需要新建一个启动文件,于是在网上查询到下列一串代码from moveit_configs_utils import MoveItConfigsBuilder from moveit_configs_utils.launches import generate_moveit_rviz_launch from launch import LaunchDescription from launch.actions import ( DeclareLaunchArgument, IncludeLaunchDescription, ) from moveit_configs_utils.launch_utils import ( add_debuggable_node, DeclareBooleanLaunchArg, ) from launch.substitutions import LaunchConfiguration from launch_ros.parameter_descriptions import ParameterValue def generate_launch_description(): moveit_config = MoveItConfigsBuilder("fhrobot11", package_name="tl_arm_moveit_config").to_moveit_configs() # 之前不知道为什么写错了,现在修改过来了。 20230612,感谢评论区的指正。 ld = LaunchDescription() # 启动move_group my_generate_move_group_launch(ld, moveit_config) # 启动rviz my_generate_moveit_rviz_launch(ld, moveit_config) return ld def my_generate_move_group_launch(ld, moveit_config): ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) ld.add_action( DeclareBooleanLaunchArg("allow_trajectory_execution", default_value=True) ) ld.add_action( DeclareBooleanLaunchArg("publish_monitored_planning_scene", default_value=True) ) # load non-default MoveGroup capabilities (space separated) ld.add_action(DeclareLaunchArgument("capabilities", default_value="")) # inhibit these default MoveGroup capabilities (space separated) ld.add_action(DeclareLaunchArgument("disable_capabilities", default_value="")) # do not copy dynamics information from /joint_states to internal robot monitoring # default to false, because almost nothing in move_group relies on this information ld.add_action(DeclareBooleanLaunchArg("monitor_dynamics", default_value=False)) should_publish = LaunchConfiguration("publish_monitored_planning_scene") move_group_configuration = { "publish_robot_description_semantic": True, "allow_trajectory_execution": LaunchConfiguration("allow_trajectory_execution"), # Note: Wrapping the following values is necessary so that the parameter value can be the empty string "capabilities": ParameterValue( LaunchConfiguration("capabilities"), value_type=str ), "disable_capabilities": ParameterValue( LaunchConfiguration("disable_capabilities"), value_type=str ), # Publish the planning scene of the physical robot so that rviz plugin can know actual robot "publish_planning_scene": should_publish, "publish_geometry_updates": should_publish, "publish_state_updates": should_publish, "publish_transforms_updates": should_publish, "monitor_dynamics": False, "use_sim_time":True } move_group_params = [ moveit_config.to_dict(), move_group_configuration, ] move_group_params.append({"use_sim_time": True}) add_debuggable_node( ld, package="moveit_ros_move_group", executable="move_group", commands_file=str(moveit_config.package_path / "launch" / "gdb_settings.gdb"), output="screen", parameters=move_group_params, extra_debug_args=["--debug"], # Set the display variable, in case OpenGL code is used internally additional_env={"DISPLAY": ":0"}, ) return ld def my_generate_moveit_rviz_launch(ld, moveit_config): """Launch file for rviz""" ld.add_action(DeclareBooleanLaunchArg("debug", default_value=False)) ld.add_action( DeclareLaunchArgument( "rviz_config", default_value=str(moveit_config.package_path / "config/moveit.rviz"), ) ) rviz_parameters = [ moveit_config.planning_pipelines, moveit_config.robot_description_kinematics, ] rviz_parameters.append({"use_sim_time": True}) add_debuggable_node( ld, package="rviz2", executable="rviz2", output="log", respawn=False, arguments=["-d", LaunchConfiguration("rviz_config")], parameters=rviz_parameters, ) return ld
但是还是会报错,报错情况如下,
现在我也不清楚到底是因为什么情况导致这些问题