ros_gazebo_gym.robot_envs.panda_env
Robot environment for the Panda Emika Franka Simulation.
Note
The panda robot environment contains two methods of controlling the robot: DIRECT
control (Default) and PROXY
based control. Initially, I abstracted all the panda
control logic away in the panda_gazebo package and made it
available through services. Later, however, I found that the service calls slowed
down the control. I then added the DIRECT control method, which directly publishes
the control commands on the controller command
topic. This control method made
the training loop two times faster. Currently, the DIRECT
mode is only available
for the position
and effort
control. Other control methods like
trajectory
and end_effector
control will use the PROXY based method.
Module Contents
Classes
Used for controlling the panda robot and retrieving sensor data. |
Attributes
- ros_gazebo_gym.robot_envs.panda_env.MOVEIT_SET_EE_POSE_TOPIC = 'panda_moveit_planner_server/panda_arm/set_ee_pose'[source]
- ros_gazebo_gym.robot_envs.panda_env.MOVEIT_GET_EE_POSE_JOINT_CONFIG_TOPIC = 'panda_moveit_planner_server/panda_arm/get_ee_pose_joint_config'[source]
- ros_gazebo_gym.robot_envs.panda_env.GET_CONTROLLED_JOINTS_TOPIC = 'panda_control_server/get_controlled_joints'[source]
- ros_gazebo_gym.robot_envs.panda_env.SET_JOINT_COMMANDS_TOPIC = 'panda_control_server/set_joint_commands'[source]
- ros_gazebo_gym.robot_envs.panda_env.SET_GRIPPER_WIDTH_TOPIC = 'panda_control_server/panda_hand/set_gripper_width'[source]
- ros_gazebo_gym.robot_envs.panda_env.SET_JOINT_TRAJECTORY_TOPIC = 'panda_control_server/panda_arm/follow_joint_trajectory'[source]
- ros_gazebo_gym.robot_envs.panda_env.FRANKA_GRIPPER_COMMAND_TOPIC = 'franka_gripper/gripper_action'[source]
- ros_gazebo_gym.robot_envs.panda_env.FRANKA_STATES_TOPIC = 'franka_state_controller/franka_states'[source]
- ros_gazebo_gym.robot_envs.panda_env.AVAILABLE_CONTROL_TYPES = ['trajectory', 'position', 'effort', 'end_effector'][source]
- ros_gazebo_gym.robot_envs.panda_env.ARM_POSITION_CONTROLLER = 'panda_arm_joint_position_controller'[source]
- ros_gazebo_gym.robot_envs.panda_env.ARM_EFFORT_CONTROLLER = 'panda_arm_joint_effort_controller'[source]
- class ros_gazebo_gym.robot_envs.panda_env.PandaEnv(robot_name_space='', robot_EE_link='panda_link8', ee_frame_offset=None, load_gripper=True, lock_gripper=False, grasping=False, control_type='effort', reset_robot_pose=True, workspace_path=None, log_reset=True, visualize=None)[source]
Bases:
ros_gazebo_gym.robot_gazebo_goal_env.RobotGazeboGoalEnv
Used for controlling the panda robot and retrieving sensor data.
To check any topic we need to have the simulations running, we need to do two things:
Un-pause the simulation: without that the stream of data doesn’t flow. This is for simulations that are paused for whatever the reason.
If the simulation was running already for some reason, we need to reset the controllers.
This has to do with the fact that some plugins with tf, don’t understand the reset of the simulation and need to be reset to work properly.
- joint_states
The current joint states.
- Type:
sensor_msgs.msg.JointState
- franka_states
The current franka states. These give robot specific information about the panda robot.
- Type:
franka_msgs.msg.FrankaState
- tf_buffer
Tf buffer object can be used to request transforms.
- Type:
tf2_ros.buffer.Buffer
- panda_gazebo
Lazy importer for the panda_gazebo package.
- franka_msgs
Lazy importer for the franka_msgs package.
Initializes a new Panda Robot environment.
- Parameters:
robot_name_space (str, optional) – The namespace the robot is on. Defaults to
""
.robot_EE_link (str, optional) – Robot end effector link name. Defaults to
panda_link8
.ee_frame_offset (dict, optional) – Dictionary containing the end effector offset. Used when retrieving and setting the end effector pose. Defaults to
None
.load_gripper (bool, optional) – Whether we want to load the parallel-jaw gripper. Defaults to
True
.lock_gripper (bool, optional) – Whether we want to lock the parallel-jaw gripper (i.e. not move). Defaults to
False
.grasping (bool, optional) – Whether we want to use the gripper for grasping. If
True
and gripper_max_effort is unset, applies 10N effort. Defaults to False.control_Type (str, optional) – The type of control you want to use for the panda robot (i.e. hand and arm). Options are:
trajectory
,position
,effort
orend_effector
. Defaults toeffort
.reset_robot_pose (bool, optional) – Boolean specifying whether to reset the robot pose when the simulation is reset. Defaults to
True
.workspace_path (str, optional) – The path of the workspace in which the panda_gazebo package should be found. Defaults to
None
.log_reset (bool, optional) – Whether we want to print a log statement when the world/simulation is reset. Defaults to
True
.visualize (bool, optional) – Whether you want to show the RViz visualization. Defaults to
None
meaning the task configuration file values will be used.
- property joints[source]
Returns the joints that can be controlled when using the current Panda arm and hand control types.
Important
For performance reasons the controlled joints are currently fetched at the first call. Please call the
refresh_joints()
method to re-fetch the currently controlled joints.
- property gripper_width[source]
Returns the gripper width as calculated based on the Panda finger joints.
- Returns:
The gripper width.
- Return type:
- property arm_positions[source]
Returns the current arm joint positions.
- Returns:
The arm joint positions.
- Return type:
- property arm_velocities[source]
Returns the current arm joint velocities.
- Returns:
The arm joint velocities.
- Return type:
- property arm_efforts[source]
Returns the current arm joint efforts.
- Returns:
The arm joint efforts.
- Return type:
- property ee_link_exists[source]
Returns whether the end effector link exists in the robot model.
- Returns:
Whether the end effector link exists in the robot model.
- Return type:
- property ee_pose[source]
Returns the current end-effector pose while taking the
ee_frame_offset
into account. If the offset is zero then it is equal to therobot_EE_link
pose.- Returns:
The end-effector pose.
- Return type:
geometry_msgs.msg.PoseStamped
- property ee_offset_is_zero[source]
Returns whether the end-effector frame offset is zero.
- Returns:
Whether the end-effector frame offset is zero.
- Return type:
- property ee_frame_offset[source]
Returns the end-effector frame offset relative to the actual ee_link (i.e.
robot_EE_link
).- Returns:
The ee frame offset pose.
- Return type:
geometry_msgs.msg.Pose
- property ee_frame_offset_stamped[source]
Returns the end-effector frame offset relative to the actual ee_link (i.e.
robot_EE_link
) as a stamped pose.- Returns:
The ee frame offset pose.
- Return type:
geometry_msgs.msg.PoseStamped
- get_ee_pose()[source]
Returns the current end-effector pose while taking the
ee_frame_offset
into account. If the offset is zero then it is equal to therobot_EE_link
pose.- Returns:
The end-effector pose.
- Return type:
geometry_msgs.msg.PoseStamped
- Raises:
ros_gazebo_gym.errors.EePoseLookupError – Error thrown when error occurred while trying to retrieve the EE pose.
- get_ee_rpy()[source]
Returns the end effector EE orientation.
- Returns:
- Object containing the roll (x),
yaw (z), pitch (y) euler angles.
- Return type:
panda_gazebo.srv.GetEeRpyResponse
- Raises:
ros_gazebo_gym.errors.EeRpyLookupError – Error thrown when error occurred while trying to retrieve the EE rpy rotation using the
get_ee_pose
service.
- get_ee_pose_joint_config(ee_pose)[source]
Returns a set of possible arm joint configurations for a given end-effector pose.
- Parameters:
ee_pose (union[
geometry_msgs.msg.Pose
, list]) – A list or pose message containing the end effector position (x, y, z) and orientation (x, y, z, w).- Returns:
- dict: Dictionary with joint positions that result in a given EE pose.
Empty dictionary is returned if no joint positions could be found.
- Return type:
obj
- set_ee_pose(ee_pose)[source]
Sets the Panda end effector pose.
- Parameters:
ee_pose (union[
geometry_msgs.msg.Pose
, list]) – A list or pose message containing the end effector position (x, y, z) and orientation (x, y, z, w).- Returns:
Boolean specifying if the ee pose was set successfully.
- Return type:
- set_joint_commands(joint_commands, arm_wait=False, hand_wait=False)[source]
Sets the Panda arm and hand joint commands based on the set
robot_control_type
.- Parameters:
- Returns:
Boolean specifying if the joint commands were set successfully.
- Return type:
- set_joint_positions(joint_commands, arm_wait=False, hand_wait=False, direct_control=True)[source]
Sets the Panda arm positions and gripper width.
- Parameters:
joint_commands (union[
panda_gazebo.srv.SetJointCommands
, list, dict]) – The Panda arm joint positions and gripper width.arm_wait (bool, optional) – Wait till the arm control has finished. Defaults to
False
.hand_wait (bool, optional) – Wait till the hand control has finished. Defaults to
False
.direct_control (bool) – Whether we want to directly control the panda by publishing to the controller topics or we want to use the
panda_gazebo
control proxy. Defaults toTrue
.
- Returns:
Boolean specifying if the joint positions were set successfully.
- Return type:
- set_joint_efforts(joint_commands, arm_wait=False, hand_wait=False, direct_control=True)[source]
Sets the Panda arm efforts and the gripper width.
- Parameters:
joint_commands (union[
panda_gazebo.srv.SetJointCommandsRequest
, list, dict]) – The panda joint efforts and gripper width.direct_control (bool) – Whether we want to directly control the panda by publishing to the controller topics or we want to use the
panda_gazebo
control proxy. Defaults toTrue
.arm_wait (bool, optional) – Wait till the arm control has finished. Defaults to
False
.hand_wait (bool, optional) – Wait till the hand control has finished. Defaults to
False
.
- Returns:
Boolean specifying if the joint efforts were set successfully.
- Return type:
- set_arm_joint_trajectory(joint_trajectory, wait=False, time_from_start=None)[source]
Sets the panda arm joint trajectory.
- Parameters:
joint_trajectory (union[
panda_gazebo.msg.FollowJointTrajectoryActionGoal
, np.array, list, dict]) – The joint trajectory you want to set.wait (bool, optional) – Wait till the control has finished. Defaults to
False
.time_from_start (float) – At what time a trajectory point should be reach in seconds. Only used when a single trajectory point is given (i.e. list, dict)
- Returns:
Boolean specifying if the joint trajectory was set successfully.
- Return type:
- Raises:
ValueError – If the input trajectory is invalid.
Note
If you input a
tuple
,list
,int
orfloat
a joint trajectory message will be constructed with one waypoint point. To set multiple waypoints, you must supply a 2D numpy array or a dictionary containing an equal number of joint commands for each joint, one for each waypoint.
- set_gripper_width(gripper_width, wait=None, grasping=None, max_effort=None)[source]
Sets the Panda gripper width.
- Parameters:
gripper_width (float) – The desired gripper width.
wait (bool, optional) – Wait till the gripper control has finished. Defaults to
False
.grasp (bool) – Whether we want to grasp a object. Defaults to
False
. Can be overwritten by setting the<NS>/control/grasping
ROS parameter.max_effort (float, optional) – The max effort used when grasping. Defaults to
None
. Meaning the action service default is used.
- Returns:
Boolean specifying if the gripper width was set successfully.
- Return type:
- lock_joints(joint_names)[source]
Locks specific panda joints.
- Parameters:
joint_names (list) – The names of the joints to lock.