diff --git a/.gitignore b/.gitignore index 16f7b04e85bc83376ca23ca1ddd1bcb54bf673ac..415be2557298dac66c3b20f0f56de6742abb46ea 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 0000000000000000000000000000000000000000..5730bd7dc168dc233f518c5e92bec3959ad71e79 --- /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 0000000000000000000000000000000000000000..10f1de79fffa42c74dd194a9fd03fe9f31a1231b --- /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 9784a18505060f26661d95a32be2107dd0d31b18..daa1a4b5a50d65e8ef53aca59f729980e72bef64 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 74990610937822c228c9229a3314c0e880e169bb..5b9d4a26671cb3fec477240305a68f2eff2d7a18 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) ), ] )