panda_gazebo.common.helpers

Module containing some additional helper functions used in the panda_gazebo package.

Module Contents

Functions

joint_state_dict_2_joint_state_msg(joint_state_dict[, ...])

Converts a joint_state dictionary into a JointState msgs.

action_dict_2_joint_trajectory_msg(action_dict[, ...])

Converts an action dictionary into a panda_gazebo FollowJointTrajectoryGoal

panda_action_msg_2_control_msgs_action_msg(...)

Converts a :class:``panda_gazebo.msg.FollowJointTrajectoryActionGoal` action

controller_list_array_2_dict(controller_list_msgs)

Converts a Controller_manager/list_controllers

translate_actionclient_result_error_code(...)

Translates the error code returned by the SimpleActionClient.get_result()

translate_moveit_error_code(moveit_error_code)

Translates a MoveIt error code object into a human readable error message.

lower_first_char(string)

De-capitalize the first letter of a string.

wrap_space_around(text)

Wrap one additional space around text if it is not already present.

list_2_human_text(input_list[, separator, end_separator])

Function converts a list of values into human readable sentence.

dict_clean(input_dict)

Removes empty dictionary keys from a dictionary and returns a cleaned up

get_unique_list(input_list[, trim])

Removes non-unique items from a list.

get_duplicate_list(input_list)

Returns the duplicates in a list.

flatten_list(input_list)

Function used to flatten a list containing sublists. It does this by calling

action_server_exists(topic_name)

Checks whether a topic contains an action server

quaternion_norm(quaternion)

Calculates the norm of a quaternion.

normalize_quaternion(quaternion)

Normalizes a given quaternion.

vector_norm(vector)

Calculates the norm of a vector.

normalize_vector(vector[, force])

Normalizes a given vector.

ros_exit_gracefully([shutdown_msg, exit_code])

Shuts down the ROS node wait until it is shutdown and exits the script.

load_panda_joint_limits()

Loads the joint limits of the Panda robot from the parameter server.

panda_gazebo.common.helpers.joint_state_dict_2_joint_state_msg(joint_state_dict, type='position')[source]

Converts a joint_state dictionary into a JointState msgs.

Parameters:
  • joint_state_dict (dict) – Dictionary specifying joint values for each joint (key).

  • type (str, optional) – The state type. Options are velocity, effort and position. Defaults to “position”.

Returns:

A JoinState message.

Return type:

sensor_msgs.msg.JointState

Raises:

ValueError – If the type is not one of the expected values.

panda_gazebo.common.helpers.action_dict_2_joint_trajectory_msg(action_dict, create_time_axis=True, time_axis_step=0.01)[source]

Converts an action dictionary into a panda_gazebo FollowJointTrajectoryGoal msgs.

Parameters:
  • action_dict (dict) – Dictionary containing actions and joints.

  • create_time_axis (bool) – Whether you want to automatically create a joint trajectory time axis if it is not yet present.

  • time_axis_step (float) – The size of the time steps used for generating the time axis.

Returns:

New FollowJointTrajectoryGoal

message.

Return type:

panda_gazebo.msg.FollowJointTrajectoryGoal

Raises:

ValuesError – When the action_dict is invalid.

panda_gazebo.common.helpers.panda_action_msg_2_control_msgs_action_msg(panda_action_msg)[source]

Converts a :class:``panda_gazebo.msg.FollowJointTrajectoryActionGoal` action message into a control_msgs/FollowJointTrajectoryGoal action message.

:param panda_action_msg control_msgs.msg.FollowJointTrajectoryGoal: Panda_gazebo

follow joint trajectory goal message.

Returns:

Control_msgs follow joint

trajectory goal message.

Return type:

control_msgs.msg.FollowJointTrajectoryGoal

Raises:

TypeError – If panda_action_msg is not of type panda_gazebo.msg.FollowJointTrajectoryGoal.

panda_gazebo.common.helpers.controller_list_array_2_dict(controller_list_msgs)[source]

Converts a Controller_manager/list_controllers message into a controller information dictionary.

Parameters:

controller_list_msgs (controller_manager_msgs.srv.ListControllersResponse) – Controller_manager/list_controllers service response message.

Returns:

Dictionary containing information about all the available controllers.

Return type:

dict

Raises:

TypeError – If controller_list_msgs is not of type controller_manager_msgs.srv.ListControllersResponse.

panda_gazebo.common.helpers.translate_actionclient_result_error_code(actionclient_retval)[source]

Translates the error code returned by the SimpleActionClient.get_result() function into a human readable error message.

Parameters:

actionclient_retval (control_msgs.msg.FollowJointTrajectoryResult) – The result that is returned by the actionlib.simple_action_client.SimpleActionClient.get_result() function.

Returns:

Error string that corresponds to the error code.

Return type:

str

Raises:

TypeError – If actionclient_retval is not of type control_msgs.msg.FollowJointTrajectoryResult.

panda_gazebo.common.helpers.translate_moveit_error_code(moveit_error_code)[source]

Translates a MoveIt error code object into a human readable error message.

Parameters:

moveit_error_code (MoveItErrorCodes) – The MoveIt error code object

Returns:

Error string that corresponds to the error code.

Return type:

str

Raises:

TypeError – If moveit_error_code is not of type moveit_msgs.msg.MoveItErrorCodes.

panda_gazebo.common.helpers.lower_first_char(string)[source]

De-capitalize the first letter of a string.

Parameters:

string (str) – The input string.

Returns:

The de-capitalized string.

Return type:

str

Raises:

TypeError – If text is not of type str.

Note

This function is not the exact opposite of the capitalize function of the standard library. For example, capitalize(‘abC’) returns Abc rather than AbC.

panda_gazebo.common.helpers.wrap_space_around(text)[source]

Wrap one additional space around text if it is not already present.

Parameters:

text (str) – Text

Returns:

Text with extra spaces around it.

Return type:

str

Raises:

TypeError – If text is not of type str.

panda_gazebo.common.helpers.list_2_human_text(input_list, separator=',', end_separator='&')[source]

Function converts a list of values into human readable sentence.

Example

Using this function a list of 4 items [item1, item2, item3, item4] becomes item2, item3 and item4.

Parameters:

input_list (list) – A input list.

Returns:

A human readable string that can be printed.

Return type:

str

Raises:

TypeError – If input_list is not of type list or tuple.

panda_gazebo.common.helpers.dict_clean(input_dict)[source]

Removes empty dictionary keys from a dictionary and returns a cleaned up dictionary. Empty meaning an empty list, string or dict or a None value.

Parameters:

input_dict (dict) – The input dictionary.

Returns:

The cleaned dictionary.

Return type:

dict

Raises:

TypeError – If input_dict is not of type dict.

panda_gazebo.common.helpers.get_unique_list(input_list, trim=True)[source]

Removes non-unique items from a list.

Parameters:
  • input_list (list) – The input list.

  • trim (list, optional) – Trim empty items. Defaults to True.

Returns:

The new list containing only unique items.

Return type:

list

Raises:

TypeError – If input_list is not of type list.

panda_gazebo.common.helpers.get_duplicate_list(input_list)[source]

Returns the duplicates in a list.

Parameters:

input_list (list) – The input list.

Returns:

The new list containing only the items that had duplicates.

Return type:

list

Raises:

TypeError – If input_list is not of type list.

panda_gazebo.common.helpers.flatten_list(input_list)[source]

Function used to flatten a list containing sublists. It does this by calling itself recursively.

Parameters:

input_list (list) – A list containing strings or other lists.

Returns:

The flattened list.

Return type:

list

Raises:

TypeError – If input_list is not of type list.

panda_gazebo.common.helpers.action_server_exists(topic_name)[source]

Checks whether a topic contains an action server is running.

Parameters:

topic_name (str) – Action server topic name.

Returns:

Boolean specifying whether the action service exists.

Return type:

bool

Raises:

TypeError – If topic_name is not of type str.

panda_gazebo.common.helpers.quaternion_norm(quaternion)[source]

Calculates the norm of a quaternion.

Parameters:

Quaternion (geometry_msgs.msg.Quaternion) – A quaternion.

Returns:

The norm of the quaternion.

Return type:

float

Raises:

TypeError – If quaternion is not of type Quaternion.

panda_gazebo.common.helpers.normalize_quaternion(quaternion)[source]

Normalizes a given quaternion.

Parameters:

quaternion (geometry_msgs.msg.Quaternion) – A quaternion.

Returns:

The normalized quaternion.

Return type:

geometry_msgs.msg.Quaternion

Raises:

TypeError – If quaternion is not of type Quaternion.

panda_gazebo.common.helpers.vector_norm(vector)[source]

Calculates the norm of a vector.

Parameters:

vector (union[list, tuple, np.array]) – A vector.

Returns:

The norm of the vector.

Return type:

float

Raises:

TypeError – If vector is not of type list or tuple.

panda_gazebo.common.helpers.normalize_vector(vector, force=True)[source]

Normalizes a given vector.

Parameters:
  • vector (union[list, tuple]) – A vector.

  • force (bool) – Whether to force the vector to have a unit length if the norm is zero. Defaults to True.

Returns:

The normalized vector.

Return type:

list

Raises:

TypeError – If vector is not of type list or tuple.

panda_gazebo.common.helpers.ros_exit_gracefully(shutdown_msg=None, exit_code=0)[source]

Shuts down the ROS node wait until it is shutdown and exits the script.

Parameters:
  • shutdown_msg (str, optional) – The shutdown message. Defaults to None.

  • exit_code (int, optional) – The exit code. Defaults to 0.

panda_gazebo.common.helpers.load_panda_joint_limits()[source]

Loads the joint limits of the Panda robot from the parameter server.

Returns:

Dictionary containing the joint position limits (i.e. min and max) for

each joint. Returns an empty dictionary if the joint limits could not be loaded.

Return type:

dict