From f251dbeed32d51cba0ac6a15045368f91473c842 Mon Sep 17 00:00:00 2001 From: sRivers <14599601+srivers@user.noreply.gitee.com> Date: Tue, 21 Jan 2025 12:17:18 +0800 Subject: [PATCH] =?UTF-8?q?update=20v1.0.14=201.=E6=B7=BB=E5=8A=A0?= =?UTF-8?q?=E5=A4=B9=E7=88=AA=E9=85=8D=E5=A5=97ros2=5Fcontrol=20yaml?= =?UTF-8?q?=E9=85=8D=E7=BD=AE=E6=96=87=E4=BB=B6=202.=E4=BF=AE=E6=94=B9laun?= =?UTF-8?q?ch=E6=96=87=E4=BB=B6=EF=BC=8C=E4=B8=8D=E5=90=AF=E5=8A=A8rviz?= =?UTF-8?q?=E6=97=B6=E4=B8=8D=E5=86=8D=E5=90=AF=E5=8A=A8joint=5Fstate=5Fpu?= =?UTF-8?q?blisher,=E9=98=B2=E6=AD=A2joint=5Fstate=5Fpublisher=E4=B8=8Ejoi?= =?UTF-8?q?nt=5Fstate=5Fbroadcaster=E5=86=B2=E7=AA=81=E7=9A=84=E6=8A=A5?= =?UTF-8?q?=E9=94=99TF=5FOLD=5FDATA?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .gitignore | 3 ++ .../config/coarm_controllers_omnipicker.yaml | 42 +++++++++++++++++++ .../config/coarm_controllers_rhino.yaml | 42 +++++++++++++++++++ coarm_gazebo/launch/coarm_gazebo.launch.py | 1 + .../launch/eye_to_hand_gazebo.launch.py | 1 + 5 files changed, 89 insertions(+) create mode 100644 coarm_gazebo/config/coarm_controllers_omnipicker.yaml create mode 100644 coarm_gazebo/config/coarm_controllers_rhino.yaml diff --git a/.gitignore b/.gitignore index 16f7b04..415be25 100644 --- a/.gitignore +++ b/.gitignore @@ -134,3 +134,6 @@ dmypy.json # Cython debug symbols cython_debug/ + +# VScode +.vscode/ diff --git a/coarm_gazebo/config/coarm_controllers_omnipicker.yaml b/coarm_gazebo/config/coarm_controllers_omnipicker.yaml new file mode 100644 index 0000000..5730bd7 --- /dev/null +++ b/coarm_gazebo/config/coarm_controllers_omnipicker.yaml @@ -0,0 +1,42 @@ +controller_manager: + ros__parameters: + update_rate: 100 # update_rate specifies how often (in Hz) the controllers should be updated. + + # Responsible for publishing the current state of the robot's joints to the /joint_states + # ROS 2 topic + joint_state_broadcaster: + type: joint_state_broadcaster/JointStateBroadcaster + + # The JointTrajectoryController allows you to send joint trajectory commands to a group + # of joints on a robot. These commands specify the desired positions for each joint. + arm_controller: + type: joint_trajectory_controller/JointTrajectoryController + +# Define the parameters for each controller +arm_controller: + ros__parameters: + joints: + - shoulder_joint + - upperArm_joint + - foreArm_joint + - wrist1_joint + - wrist2_joint + - wrist3_joint + - omnipicker_hand_narrow1_joint + # The controller will expect position commands as input for each of these joints. + command_interfaces: + - position + # Tells the controller that it should expect to receive position data as the state + # feedback from the hardware interface, + state_interfaces: + - position + # If true, When set to true, the controller will not use any feedback from the system + # (e.g., joint positions, velocities, efforts) to compute the control commands. + open_loop_control: false + # When set to true, it allows the controller to integrate the trajectory goals it receives. + # This means that if the goal trajectory only specifies positions, the controller will + # numerically integrate the positions to compute the velocities and accelerations required + # to follow the trajectory. + allow_integration_in_goal_trajectories: true + # Allow non-zero velocity at the end of the trajectory + allow_nonzero_velocity_at_trajectory_end: true diff --git a/coarm_gazebo/config/coarm_controllers_rhino.yaml b/coarm_gazebo/config/coarm_controllers_rhino.yaml new file mode 100644 index 0000000..10f1de7 --- /dev/null +++ b/coarm_gazebo/config/coarm_controllers_rhino.yaml @@ -0,0 +1,42 @@ +controller_manager: + ros__parameters: + update_rate: 100 # update_rate specifies how often (in Hz) the controllers should be updated. + + # Responsible for publishing the current state of the robot's joints to the /joint_states + # ROS 2 topic + joint_state_broadcaster: + type: joint_state_broadcaster/JointStateBroadcaster + + # The JointTrajectoryController allows you to send joint trajectory commands to a group + # of joints on a robot. These commands specify the desired positions for each joint. + arm_controller: + type: joint_trajectory_controller/JointTrajectoryController + +# Define the parameters for each controller +arm_controller: + ros__parameters: + joints: + - shoulder_joint + - upperArm_joint + - foreArm_joint + - wrist1_joint + - wrist2_joint + - wrist3_joint + - rhino_left_knuckle_joint + # The controller will expect position commands as input for each of these joints. + command_interfaces: + - position + # Tells the controller that it should expect to receive position data as the state + # feedback from the hardware interface, + state_interfaces: + - position + # If true, When set to true, the controller will not use any feedback from the system + # (e.g., joint positions, velocities, efforts) to compute the control commands. + open_loop_control: false + # When set to true, it allows the controller to integrate the trajectory goals it receives. + # This means that if the goal trajectory only specifies positions, the controller will + # numerically integrate the positions to compute the velocities and accelerations required + # to follow the trajectory. + allow_integration_in_goal_trajectories: true + # Allow non-zero velocity at the end of the trajectory + allow_nonzero_velocity_at_trajectory_end: true diff --git a/coarm_gazebo/launch/coarm_gazebo.launch.py b/coarm_gazebo/launch/coarm_gazebo.launch.py index 9784a18..daa1a4b 100644 --- a/coarm_gazebo/launch/coarm_gazebo.launch.py +++ b/coarm_gazebo/launch/coarm_gazebo.launch.py @@ -148,6 +148,7 @@ def prepare_launch_description(): name='joint_state_publisher', parameters=[ {'source_list': ['joint_states'], 'rate': 50.0}], + condition=IfCondition(launch_rviz), ), ] ) diff --git a/coarm_gazebo/launch/eye_to_hand_gazebo.launch.py b/coarm_gazebo/launch/eye_to_hand_gazebo.launch.py index 7499061..5b9d4a2 100644 --- a/coarm_gazebo/launch/eye_to_hand_gazebo.launch.py +++ b/coarm_gazebo/launch/eye_to_hand_gazebo.launch.py @@ -191,6 +191,7 @@ def prepare_launch_description(): name='joint_state_publisher', parameters=[ {'source_list': ['joint_states'], 'rate': 50.0}], + condition=IfCondition(launch_rviz) ), ] ) -- Gitee