ros_gazebo_gym.robot_envs

Contains all ros_gazebo_gym robot environments.

Submodules

Package Contents

Classes

PandaEnv

Used for controlling the panda robot and retrieving sensor data.

class ros_gazebo_gym.robot_envs.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:

  1. Un-pause the simulation: without that the stream of data doesn’t flow. This is for simulations that are paused for whatever the reason.

  2. 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.

robot_name_space

The robot name space.

Type:

str

reset_controls

Whether the controllers are reset when the simulation is reset.

Type:

bool

The link used for the end effector control.

Type:

str

ee_frame_offset

Dictionary containing the used end effector offset.

Type:

dict

load_gripper

Whether the gripper was loaded.

Type:

bool

lock_gripper

Whether the gripper should be locked (i.e. not move).

Type:

bool

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.

Type:

ros_gazebo_gym.core.LazyImporter

franka_msgs

Lazy importer for the franka_msgs package.

Type:

ros_gazebo_gym.core.LazyImporter

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 or end_effector. Defaults to effort.

  • 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

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

Returns the gripper width as calculated based on the Panda finger joints.

Returns:

The gripper width.

Return type:

float

property arm_positions

Returns the current arm joint positions.

Returns:

The arm joint positions.

Return type:

dict

property arm_velocities

Returns the current arm joint velocities.

Returns:

The arm joint velocities.

Return type:

dict

property arm_efforts

Returns the current arm joint efforts.

Returns:

The arm joint efforts.

Return type:

dict

property robot_control_type

Returns the currently set robot control type.

property in_collision

Whether the robot is in collision.

property locked_joints

Returns the currently locked joints.

Returns whether the end effector link exists in the robot model.

Returns:

Whether the end effector link exists in the robot model.

Return type:

bool

property ee_pose

Returns the current end-effector pose while taking the ee_frame_offset into account. If the offset is zero then it is equal to the robot_EE_link pose.

Returns:

The end-effector pose.

Return type:

geometry_msgs.msg.PoseStamped

property ee_offset_is_zero

Returns whether the end-effector frame offset is zero.

Returns:

Whether the end-effector frame offset is zero.

Return type:

bool

property ee_frame_offset

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

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 the robot_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:

bool

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:
  • 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.

Returns:

Boolean specifying if the joint commands were set successfully.

Return type:

bool

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 to True.

Returns:

Boolean specifying if the joint positions were set successfully.

Return type:

bool

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 to True.

  • 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:

bool

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:

bool

Raises:

ValueError – If the input trajectory is invalid.

Note

If you input a tuple, list, int or float 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:

bool

lock_joints(joint_names)[source]

Locks specific panda joints.

Parameters:

joint_names (list) – The names of the joints to lock.

unlock_joints(joint_names)[source]

Unlocks specific panda joints.

Parameters:

joint_names (list) – The names of the joints to unlock.

refresh_joints()[source]

Re-fetches the currently active joints.