panda_gazebo.core
Contains the core components (classes and functions) that are needed for creating the panda_gazebo simulation.
Submodules
Package Contents
Classes
Controller server used to send control commands to the simulated Panda Robot. |
|
Used for switching the Panda robot controllers. |
|
Used to control or request information from the Panda Robot. This is done using |
- class panda_gazebo.core.PandaControlServer(autofill_traj_positions=False, load_gripper=True, load_set_joint_commands_service=True, load_arm_follow_joint_trajectory_action=False, load_extra_services=False, controllers_check_rate=CONTROLLER_INFO_RATE)[source]
Bases:
object
Controller server used to send control commands to the simulated Panda Robot.
- joint_states
The current joint states.
- Type:
sensor_msgs.JointState
- arm_joint_positions_threshold
The current threshold for determining whether the arm joint positions are within the given setpoint.
- Type:
- arm_joint_efforts_threshold
The current threshold for determining whether the arm joint efforts are within the given setpoint.
- Type:
- arm_velocity_threshold
The current threshold for determining whether the arm has zero velocity.
- Type:
Initialise PandaControlServer object.
- Parameters:
autofill_traj_positions (bool, optional) – Whether you want to automatically set the current states as positions when the positions field of the joint trajectory message is left empty. Defaults to
False
.load_gripper (boolean, optional) – Whether we also want to load the gripper control services.
load_set_joint_commands_service (boolean, optional) – Whether the set joint commands service should be loaded. This service is used by the ros_gazebo_gym package when the control type is NOT set to
trajectory
. Defaults, toTrue
.load_arm_follow_joint_trajectory_action (boolean, optional) – Whether the arm follow joint trajectory action should be loaded. This service is used by the ros_gazebo_gym package when the control type is set to
trajectory
. Defaults, toFalse
.load_extra_services (bool, optional) – Whether to load extra services that are not used by the ros_gazebo_gym package. Defaults to
False
.controllers_check_rate (float, optional) – Rate at which the availability of the used controllers is checked. Setting this to
-1
will check at every time step. Defaults to0.1
Hz.
Warning
Please note that increasing the
controllers_check_rate
decreases the control frequency.- property arm_trajectory_action_preempted
Returns whether the arm joint trajectory action server is preempted.
- property controlled_joints
Returns the joints that can be controlled by a each control type.
Important
This does not mean that the necessary controller is running. It only means that the controller was loaded and can be used to control the joints when it is started.
- Returns:
- A dictionary containing the joints that are controlled when using a
given control type (i.e.
control_type
>``control_group``>``controller``).
- Return type:
- property joint_controllers
Retrieves the controllers which are currently loaded to control each joint.
- Returns:
- A dictionary where the keys are joint names and the values are
lists of controllers that can control the joint.
- Return type:
- property controllers
Retrieves info about the loaded controllers.
Note
This method is cached to reduce the number of calls to the controller manager and therefore increase performance.
- Returns:
Dictionary with information about the currently loaded controllers.
- Return type:
- class panda_gazebo.core.PandaControlSwitcher(connection_timeout=10, verbose=True, robot_name_space='')[source]
Bases:
object
Used for switching the Panda robot controllers.
Initialise PandaControlSwitcher object.
- Parameters:
connection_timeout (str, optional) – The timeout for connecting to the controller_manager services. Defaults to 10 sec.
verbose (bool, optional) – Whether to display debug log messages. Defaults to
True
.robot_name_space (string, optional) – The namespace the robot, and thus the ‘controller_manager’ is on. Defaults to
""
.
- property arm_control_types
Returns the currently active arm control types. Returns empty list when no control type is enabled.
- property hand_control_types
Returns the currently active hand control types. Returns empty when no control type is enabled.
- wait_for_control_type(control_group, control_type, timeout=None, rate=10)[source]
Function that can be used to wait till all the controllers used for a given ‘control_group’ and ‘control_type’ are running. Useful four when you expect a launch file to load certain controllers.
- Parameters:
control_group (str) – The control group of which you want the switch the control type. Options are
hand
orarm
.control_type (str) – The robot control type you want to switch to for the given ‘control_group’. Options are:
trajectory
,position
andeffort
.timeout (float, optional) – The function timeout. Defaults to
None
meaning the function will wait for ever.rate (int, optional) – The ‘control_type’ check rate. Defaults to 10 hz.
- Raises:
TimeoutError – Thrown when the set timeout has passed.
- switch(control_group, control_type, load_controllers=True, timeout=3, verbose=None)[source]
Switch Panda robot control type. This function stops all currently running controllers and starts the required controllers for a given control type.
- Parameters:
control_group (str) – The control group of which you want the switch the control type. Options are
hand
orarm
.control_type (str) – The robot control type you want to switch to for the given ‘control_group’. Options are:
trajectory
,position
andeffort
.load_controllers (bool) – Try to load the required controllers for a given control_type if they are not yet loaded.
timeout (int, optional) – The timeout for switching to a given controller. Defaults to
3
sec.verbose (bool, optional) – Whether to display debug log messages. Defaults to verbose value set during the class initiation.
- Returns:
Contains information about whether the switch operation was successful ‘success’ and the previously used controller ‘prev_control_type’.
- Return type:
- class panda_gazebo.core.PandaMoveItPlannerServer(arm_move_group='panda_arm', arm_ee_link='panda_link8', hand_move_group='panda_hand', load_gripper=True, load_set_ee_pose_service=True, load_extra_services=False)[source]
Bases:
object
Used to control or request information from the Panda Robot. This is done using the MoveIt
moveit_commander
module.- robot
The MoveIt robot commander object.
- Type:
moveit_commander.robot.RobotCommander
- scene
The MoveIt robot scene commander object.
- Type:
moveit_commander.planning_scene_interface.PlanningSceneInterface
- move_group_arm
The MoveIt arm move group object.
- Type:
moveit_commander.move_group.MoveGroupCommander
- move_group_hand
The MoveIt hand move group object.
- Type:
moveit_commander.move_group.MoveGroupCommander
- ee_pose_target
The last set ee pose.
- Type:
geometry_msgs.msg.Pose
- joint_positions_target
Dictionary containing the last Panda arm and hand joint positions setpoint.
- Type:
Initialise PandaMoveItPlannerServer object.
- Parameters:
arm_move_group (str, optional) – The name of the move group you want to use for controlling the Panda arm. Defaults to
panda_arm
.arm_ee_link (str, optional) – The end effector you want MoveIt to use when controlling the Panda arm. Defaults to
panda_link8
.hand_move_group (str, optional) – The name of the move group you want to use for controlling the Panda hand. Defaults to
panda_hand
.load_gripper (boolean, optional) – Whether we also want to load the gripper control services. Defaults to
True
.load_set_ee_pose_service (boolean, optional) – Whether the set ee pose service should be loaded. This service is used by the ros_gazebo_gym package when the control type is set to
trajectory
. Defaults, toTrue
.load_extra_services (bool, optional) – Whether to load extra services that are not used by the ros_gazebo_gym package. Defaults to
False
.