- Python 3.9.10 with TensorFlow Agents version 0.10.0
- ROS Melodic
- libfranka 0.9.0
- franka_ros 0.9.0 + commits
- Tested with Franka Emika Panda Robot system version 4.2.1
- Create a ROS catkin workspace with the following packages:
- this (
softgrasp_ros_controllers
), softgrasp_ros
,- our fork of
franka_ros
- Download a checkpoint from here and unzip it in the
policies
directory. Denote its path aspolicies/$EXP_NAME
. Also note the$CKPT_NAME
from that table. - Activate the catkin workspace created above, and then launch:
roslaunch softgrasp_ros_controllers policy_name:=softgrasp robot_ip:=<robot IP> exp_name:=$EXP_NAME ckpt_dirname:=$CKPT_NAME
.
src/tf_policy_controller.cpp
implements a ROS controller that- creates a "goal" for the policy server using robot model and state
- composes the current EEF pose with pose delta predicted by the policy server to get EEF target
- runs high-frequency task space impedance control with the EEF target
- policy server is implemented by Python3 nodes in
nodes
- policy observation and action are in (pos, quat) format
chrony
time synchronization
- Match
kp
from robosuiteosc_pose.json
withfranka_example_controllers/cfg/compliance_param.yaml
on the realtime ROS computer - Match
{input,output}_{min,max}
fromosc_pose.json
with those variables inTFPolicyActionServer
- Run
sim.launch
orreal.launch
withpolicy_name:=circle
rosbag record tf tf_static -o $HOME/circle.bag
roslaunch softgrasp_ros_controllers circle_sanity_check.launch bag_filename:=$HOME/circle.bag
They are stored in launch/static_poses.launch
.
cTw
contains the output ofmarker_pose
fromsoftgrasp_ros
with just the table-affixed marker visiblecTg
contains the ouput ofmarker_pose
fromsoftgrasp_ros
with the table-affixed marker occluded and goal marker card visible- When the camera location is moved, update both
cTw
andcTg
static transform broadcasters - Procedure for
wTb
:- keep just
cTw
uncommented roslaunch softgrasp_ros_controllers static_poses.launch
roslaunch realsense2_camera rs_camera.launch
roslaunch <camera_pose.launch>
, wherecamera_pose.launch
is the launch file generated by the hand-eye calibrationrosrun tf tf_echo world_table panda_link0
- Copy-paste its output to
wTb
, remembering to either normalize the quaternion, or if using Euler angles, reverse the order of RPY because TF's static transform broadcaster requires YPR
- keep just
- The
camera_link_broadcaster
node in<camera_pose.launch>
contains the info generated by hand-eye calibration