Kinovarobotics / ros2_kortex

ROS2 driver for the Gen3 Kinova robot arm
Other
51 stars 48 forks source link

Admittance mode and blocked control? #209

Closed cjiang2 closed 7 months ago

cjiang2 commented 8 months ago

Hello, I'm using ROS2 to communicate with a real-world gen3 arm, following the instructions as:

ros2 launch kortex_bringup gen3.launch.py \
  robot_ip:=192.168.1.10 \
  use_fake_hardware:=false \
  use_internal_bus_gripper_comm:=false \
  launch_rviz:=false

Joint states can be successfully read, and be manipulated with joint_trajectory_controller. However, after using the ros2 gen3.launch, gen3 will be unresponsive to admittance mode, even after ros2 driver being stopped. All control inputs using the Kinova Web app will be blocked as well. The robot can only be controlled, using admittance mode, or web app interface again, after a restart.

I wonder if this is an expected behavior? Or is there any way to correct this?

Side note: After launching the ros2 driver, the servoing mode is switched from Single-Level servoing to Low-level servoing. I wonder if this is what's blocking the control?

smoya23 commented 7 months ago

Hi @cjiang2,

It is an expected behaviour in the sense that the ROS2 Kortex driver switches the arm to Low-level servoing mode when being controller by the joint_trajectory_controlled. In Low-level servoing mode, the arm will only respond to joint position commands, so that explains why your arm seems "blocked" when trying to control it in admittance mode. Without having to restart your arm, you can change back the servoing mode to Single-level by activating the twist controller via a service call if you haven't shut down the ROS2 driver :

ros2 service call /controller_manager/switch_controller controller_manager_msgs/srv/SwitchController "{
  activate_controllers: [twist_controller],
  deactivate_controllers: [joint_trajectory_controller],
  strictness: 1,
  activate_asap: true,
}"

If you have already shut down the ROS2 driver, you can change the servoing mode via the webapp by going to the Configurations/Robot/Base page and clicking on 'Set Single Client Servoing Mode'.

Hoping this clarifies it for you, don't hesitate if there is anything else!

Best, Santiago

cjiang2 commented 7 months ago

Hi @cjiang2,

It is an expected behaviour in the sense that the ROS2 Kortex driver switches the arm to Low-level servoing mode when being controller by the joint_trajectory_controlled. In Low-level servoing mode, the arm will only respond to joint position commands, so that explains why your arm seems "blocked" when trying to control it in admittance mode. Without having to restart your arm, you can change back the servoing mode to Single-level by activating the twist controller via a service call if you haven't shut down the ROS2 driver :

ros2 service call /controller_manager/switch_controller controller_manager_msgs/srv/SwitchController "{
  activate_controllers: [twist_controller],
  deactivate_controllers: [joint_trajectory_controller],
  strictness: 1,
  activate_asap: true,
}"

If you have already shut down the ROS2 driver, you can change the servoing mode via the webapp by going to the Configurations/Robot/Base page and clicking on 'Set Single Client Servoing Mode'.

Hoping this clarifies it for you, don't hesitate if there is anything else!

Best, Santiago

Many thanks for the clarification. I will consider the issue closed, and will reach out should I get more questions.