-
Notifications
You must be signed in to change notification settings - Fork 47
Manipulation and Grippers
The USV supports one robot manipulator mounted on its platform. The arm provided is Oberon7 (based on the Schilling Orion7P manipulator)
-
First launch the coast environment:
ros2 launch mbzirc_ros competition_local.launch.py ign_args:="-v 4 -r coast.sdf"
The world may take a minute to load.
-
Spawn the USV with the Oberon7 arm and Oberon7 gripper at the location of the dock by the start gate
ros2 launch mbzirc_ign spawn.launch.py name:=usv world:=coast model:=usv x:=-1462 y:=-16.5 z:=0.3 R:=0 P:=0 Y:=0 arm:=mbzirc_oberon7_arm gripper:=mbzirc_oberon7_gripper
Note the the new
arm
andgripper
arguments in the spawn script.-
arm
: Currently onlymbzirc_oberon7_arm
is supported. -
gripper
: Available grippers are:mbzirc_oberon7_gripper
andmbzirc_suction_gripper
The robot and the arm may take some time to load. The arm will slowly lift up once the simulation resumes after loading.
-
-
Now try publishing messages to move the arm and gripper. For example:
# arm ros2 topic pub --once /usv/arm/joint/azimuth/cmd_pos std_msgs/msg/Float64 'data: 0.5' ros2 topic pub --once /usv/arm/joint/shoulder/cmd_pos std_msgs/msg/Float64 'data: 0.5' ros2 topic pub --once /usv/arm/joint/elbow/cmd_pos std_msgs/msg/Float64 'data: 0.5' ros2 topic pub --once /usv/arm/joint/roll/cmd_pos std_msgs/msg/Float64 'data: 0.5' ros2 topic pub --once /usv/arm/joint/pitch/cmd_pos std_msgs/msg/Float64 'data: 0.5' ros2 topic pub --once /usv/arm/joint/wrist/cmd_pos std_msgs/msg/Float64 'data: 0.5' # gripper ros2 topic pub --once /usv/arm/gripper/joint/finger_left/cmd_pos std_msgs/msg/Float64 'data: 0.5' ros2 topic pub --once /usv/arm/gripper/joint/finger_right/cmd_pos std_msgs/msg/Float64 'data: 0.5'
The arm and gripper are joint position controllers. See the Manipulator section in the Robots and sensor APIs page for a list of APIs.
-
You can access the arm and gripper joint states to get feedback.
# arm joint states ros2 topic echo /usv/arm/joint_states # gripper joint states ros2 topic echo /usv/arm/gripper/joint_states
-
The arm wrist also has a force-torque sensor that lets you get force and torque feedback. If you're using the Oberon7 finger gripper, there is also a force-torque sensor on each finger.
# arm wrist force and torque feedback ros2 topic echo /usv/arm/wrist/joint/wrench # gripper finger force and torque feedback ros2 topic echo /usv/arm/gripper/joint/finger_right/wrench ros2 topic echo /usv/arm/gripper/joint/finger_left/wrench
The quadrotor and hexrotor supports grippers mounted on the bottom of the UAV platform. The fixed wing UAV will not be able to fly with grippers attached.
-
First launch the coast environment:
ros2 launch mbzirc_ros competition_local.launch.py ign_args:="-v 4 -r coast.sdf"
The world may take a minute to load.
-
Spawn a quadrotor with the suction gripper at the start gate
ros2 launch mbzirc_ign spawn.launch.py name:=quadrotor_1 world:=coast model:=mbzirc_quadrotor x:=-1500 y:=-1 z:=4.3 R:=0 P:=0 Y:=0 gripper:=mbzirc_suction_gripper
-
Spawn a hexdrotor with the Oberon7 gripper next to the quadrotor
ros2 launch mbzirc_ign spawn.launch.py name:=hexrotor_1 world:=coast model:=mbzirc_hexrotor x:=-1500 y:=1 z:=4.3 R:=0 P:=0 Y:=0 gripper:=mbzirc_oberon7_gripper
-
Once you are able to fly and land the a UAV with suction gripper onto a target object, you can enable suction by running:
ros2 topic pub --once /quadrotor_1/gripper/suction_on std_msgs/msg/Bool 'data: true'
Note that the UAVs with grippers have stronger motors and different controller parameters so they can take off with heavier mass and grasp objects ~1kg. Their flight behavior will be different from UAVs without a gripper. You will also notice that a UAV with gripper lifts off with an item in its gripper, it will become less stable.
If you are testing UAV grasping in the Simple Demo or Coast environment, please note that the objects only become free to move once the target vessel has been identified, see the Objects On Vessel section.
For local practice and testing, we have put together simple test scenarios demonstrating the use of UAVs for lifting and dragging objects with a suction gripper. The first world shows a quadrotor lifting a small object with a suction gripper.
-
Launch the test environment:
ros2 launch ros_ign_gazebo ign_gazebo.launch.py ign_args:="-v 4 -r test/simple_demo_manip.sdf"
-
Spawn a quadrotor with suction gripper over the small object
ros2 launch mbzirc_ign spawn.launch.py name:=quadrotor_1 world:=simple_demo model:=mbzirc_quadrotor type:=uav x:=-0 y:=2.05 z:=1.92 R:=0 P:=0 Y:=0 gripper:=mbzirc_suction_gripper
-
Remove a test cube that sits in between the quadrotor and the small object so that the quadrotor's suction gripper comes in full contact with surface of the small object
ign service -s /world/simple_demo/remove --reqtype ignition.msgs.Entity --reptype ignition.msgs.Boolean --timeout 300 --req 'name: "box1kg" type: MODEL'
-
Enable suction
ros2 topic pub --once /quadrotor_1/gripper/suction_on std_msgs/msg/Bool 'data: True'
-
Now send a positive z velocity command to make the quadrotor take off with the small object
ros2 topic pub --once /quadrotor_1/cmd_vel geometry_msgs/msg/Twist '{linear: {x: 0.0, y: 0.0, z: 5}, angular: {x: 0.0, y: 0.0, z: 0.0}}'
Large objects on the other hand are too heavy for UAVs to lift. The second world shows how you can use 2 UAVs to collaborate and drag moving a large object across the deck of a vessel. The idea is to move the large objects as close as possible to the edge of of the vessel so that the robot manipulator on the USV can reach in and pick up the large objects.
-
Launch the test world
ros2 launch mbzirc_ros competition_local.launch.py ign_args:="-v 4 -r test/multi_drone_drag.sdf"
-
Spawn 2 quadrotors over a large object by running our demo spawn script,
multi_uav_drag_demo.launch.py
:ros2 launch mbzirc_ign multi_uav_drag_demo.launch.py
-
Execute another demo script,
multi_uav_demo.py
, that enables suction and sends velocity commands to the quadrotors to drag the large object.ros2 run mbzirc_ign multi_uav_demo.py -x -5 -y -5 -z 5
Because there is a slight slope on this vessel's deck, the object tends to slide downhill a bit. So give it an initial negative x velocity command to counter the sliding motion.