panda_autograsp package

Submodules

panda_autograsp.loggers module

Utility class for logging. This class is a wrapper around the original logging module logging and can be used to apply the panda_autograsp formatters, filters and handlers to the logging object.

panda_autograsp.loggers.clear_root()[source]

Function used to reset the root logger.

panda_autograsp.loggers.configure_root(log_level=20)[source]

Function used to configure the root logger.

Parameters:log_level (int, optional) – The log level, by default ROOT_LOG_LEVEL
Returns:Root logger.
Return type:Logger
panda_autograsp.loggers.add_root_log_file(log_file, mode='a', encoding=None, delay=False)[source]

Add a log file to the root logger.

Parameters:
  • log_file (str) – The path to the log file.
  • mode (str) – Log file writing mode, by default ‘a’.
  • encoding (str) – File encoding used, by default None.
  • delay (str) – If delay is true, then file opening is deferred until the first call to emit(), by default False.
class panda_autograsp.loggers.Logger[source]

Bases: object

Panda autograsp Logger class.

ROOT_CONFIGURED = False
static clear_root()[source]

Reset root logger.

static reconfigure_root()[source]

Reconfigure the root logger.

static get_logger(name=None, log_level=20, log_file=None, silence=False, mode='a', encoding=None, delay=False)[source]

Build a logger. All logs will be propagated up to the root logger if not silenced. If log_file is provided, logs will be written out to that file. If no logger name is given, log_file will be handed the root logger, otherwise it will only be used by this particular logger.

Parameters:
  • name (str) – The name of the logger to be built, by default “” thus formatting the root logger.
  • log_level (int) – The log level. See the python logging module documentation for possible enum values.
  • log_file (str) – The path to the log file to log to.
  • silence (bool) – Whether or not to silence this logger. If it is silenced, the only way to get output from this logger is through a non-global log file.
  • mode (str) – Log file writing mode, by default ‘a’.
  • encoding (str) – File encoding used, by default None.
  • delay (str) – If delay is true, then file opening is deferred until the first call to emit(), by default False.
Returns:

A custom logger.

Return type:

Logger

static add_log_file(log_file=None, logger=None, mode='a', encoding=None, delay=False)[source]

Add a log file to this logger. If no logger is given, log_file will be handed the root logger, otherwise it will only be used by this particular logger.

Parameters:
  • log_file (str) – The path to the log file to log to.
  • logger (logging.Logger) – The logger.
  • mode (str) – Log file writing mode, by default ‘a’.
  • encoding (str) – File encoding used, by default None.
  • delay (str) – If delay is true, then file opening is deferred until the first call to emit(), by default False.

panda_autograsp.moveit_collision_objects module

Module that contains a number of constraint object classes that can be used to add constraint to the moveit planning scene. It was created since the moveit_commander doesn’t yet contain a addCollisionObjects method. As a result using the standard collision_object_msgs and shape_msgs was not ideal.

class panda_autograsp.moveit_collision_objects.Box(name, size_x=1.0, size_y=1.0, size_z=1.0, x_pos=0.0, y_pos=0.0, z_pos=0.0, x_rot=0.0, y_rot=0.0, z_rot=0.0, w_rot=1.0, reference_frame='world')[source]

Bases: object

Moveit Box collision object class.

type

Collision object type.

Type:str
name

The name of the object.

Type:str
size

The size of the box specified as (x, y, z).

Type:tuple
pose

The pose of the collision object.

Type:geometry_msgs.PoseStamed
__init__(name, size_x=1.0, size_y=1.0, size_z=1.0, x_pos=0.0, y_pos=0.0, z_pos=0.0, x_rot=0.0, y_rot=0.0, z_rot=0.0, w_rot=1.0, reference_frame='world')[source]
Parameters:
  • name (str) – The name of the object.
  • size_x (float, optional) – The x-dimensions size of the box, by default 1.0
  • size_y (float, optional) – The y-dimensions size of the box, by default 1.0
  • size_z (float, optional) – The z-dimensions size of the box, by default 1.0
  • x_pos (float, optional) – The x position in link_name frame, by default 0.0.
  • y_pos (float, optional) – The y position in link_name frame, by default 0.0.
  • z_pos (float, optional) – The z position in link_name frame, by default 0.0.
  • x_rot (float, optional) – The x orientation relative to the link_name frame, by default 0.0.
  • y_rot (float, optional) – The y orientation relative to the link_name frame, by default 0.0.
  • z_rot (float, optional) – The z orientation relative to the link_name frame, by default 0.0.
  • w_rot (float, optional) – The w orientation relative to the link_name frame, by default 1.0.
  • reference_frame (str, optional) – The frame in which the pose is expressed, by default world.
size

Get the size of the collision object.

class panda_autograsp.moveit_collision_objects.Plane(name, normal_x=0.0, normal_y=0.0, normal_z=1.0, offset=0.0, x_pos=0.0, y_pos=0.0, z_pos=0.0, x_rot=0.0, y_rot=0.0, z_rot=0.0, w_rot=1.0, reference_frame='world')[source]

Bases: object

Moveit Cube collision object class.

Note

This class uses the plane equation Ax+Bx+Cz + D = 0 to construct the plane. In this A,B,C represent the the coordinates of the plane normal (Orientation) and D the offset to the normal.

type

Collision object type.

Type:str
name

The name of the object.

Type:str
normal

Plane normal specified as (x, y, z).

Type:list
offset

Plane offset relative to the normal.

Type:float
pose

The pose of the collision object.

Type:geometry_msgs.PoseStamed
__init__(name, normal_x=0.0, normal_y=0.0, normal_z=1.0, offset=0.0, x_pos=0.0, y_pos=0.0, z_pos=0.0, x_rot=0.0, y_rot=0.0, z_rot=0.0, w_rot=1.0, reference_frame='world')[source]
Parameters:
  • name (str) – The name of the object.
  • normal_x (float, optional) – The normal vector x coordinate, by default 0.0.
  • normal_y (float, optional) – The normal vector y coordinate, by default 0.0.
  • normal_z (float, optional) – The normal vector z coordinate, by default 1.0.
  • offset (py:obj:float, optional) – Plane offset relative to the normal, by default 0.0
  • x_pos (float, optional) – The x position in link_name frame, by default 0.0.
  • y_pos (float, optional) – The y position in link_name frame, by default 0.0.
  • z_pos (float, optional) – The z position in link_name frame, by default 0.0.
  • x_rot (float, optional) – The x orientation relative to the link_name frame, by default 0.0.
  • y_rot (float, optional) – The y orientation relative to the link_name frame, by default 0.0.
  • z_rot (float, optional) – The z orientation relative to the link_name frame, by default 0.0.
  • w_rot (float, optional) – The w orientation relative to the link_name frame, by default 1.0.
  • reference_frame (str, optional) – The frame in which the pose is expressed, by default world.
normal

The plane normal.

class panda_autograsp.moveit_collision_objects.Cylinder(name, height=1.0, radius=1.0, x_pos=0.0, y_pos=0.0, z_pos=0.0, x_rot=0.0, y_rot=0.0, z_rot=0.0, w_rot=1.0, reference_frame='world')[source]

Bases: object

Moveit cylinder collision object class.

type

Collision object type.

Type:str
name

The name of the object.

Type:str
height

The height of the cylinder.

Type:float
radius

The radius of the cylinder.

Type:float
x_pos

The x position in link_name frame.

Type:float
y_pos

The y position in link_name frame.

Type:float
z_pos

The z position in link_name frame.

Type:float
x_rot

The x orientation relative to the link_name frame.

Type:float
y_rot

The y orientation relative to the link_name frame.

Type:float
z_rot

The z orientation relative to the link_name frame.

Type:float
w_rot

The w orientation relative to the link_name frame.

Type:float
pose

The object pose.

Type:geometry_msgs.PoseStamped
__init__(name, height=1.0, radius=1.0, x_pos=0.0, y_pos=0.0, z_pos=0.0, x_rot=0.0, y_rot=0.0, z_rot=0.0, w_rot=1.0, reference_frame='world')[source]
Parameters:
  • name (str) – The name of the object.
  • height (float, optional) – The height of the cylinder, by default 1.0
  • radius (float, optional) – The radius of the cylinder, by default 1.0.
  • x_pos (float, optional) – The x position in link_name frame, by default 0.0.
  • y_pos (float, optional) – The y position in link_name frame, by default 0.0.
  • z_pos (float, optional) – The z position in link_name frame, by default 0.0.
  • x_rot (float, optional) – The x orientation relative to the link_name frame, by default 0.0.
  • y_rot (float, optional) – The y orientation relative to the link_name frame, by default 0.0.
  • z_rot (float, optional) – The z orientation relative to the link_name frame, by default 0.0.
  • w_rot (float, optional) – The w orientation relative to the link_name frame, by default 1.0.
  • reference_frame (str, optional) – The frame in which the pose is expressed, by default world.
class panda_autograsp.moveit_collision_objects.Sphere(name, radius=1.0, x_pos=0.0, y_pos=0.0, z_pos=0.0, x_rot=0.0, y_rot=0.0, z_rot=0.0, w_rot=1.0, reference_frame='world')[source]

Bases: object

Moveit sphere collision object class.

type

Collision object type.

Type:str
name

The name of the object.

Type:str
radius

The radius of the sphere.

Type:float
x_pos

The x position in link_name frame.

Type:float
y_pos

The y position in link_name frame.

Type:float
z_pos

The z position in link_name frame.

Type:float
x_rot

The x orientation relative to the link_name frame.

Type:float
y_rot

The y orientation relative to the link_name frame.

Type:float
z_rot

The z orientation relative to the link_name frame.

Type:float
w_rot

The w orientation relative to the link_name frame.

Type:float
pose

The object pose.

Type:geometry_msgs.PoseStamped
__init__(name, radius=1.0, x_pos=0.0, y_pos=0.0, z_pos=0.0, x_rot=0.0, y_rot=0.0, z_rot=0.0, w_rot=1.0, reference_frame='world')[source]
Parameters:
  • name (str) – The name of the object.
  • radius (float, optional) – The radius of the sphere, by default 1.0.
  • x_pos (float, optional) – The x position in link_name frame, by default 0.0.
  • y_pos (float, optional) – The y position in link_name frame, by default 0.0.
  • z_pos (float, optional) – The z position in link_name frame, by default 0.0.
  • x_rot (float, optional) – The x orientation relative to the link_name frame, by default 0.0.
  • y_rot (float, optional) – The y orientation relative to the link_name frame, by default 0.0.
  • z_rot (float, optional) – The z orientation relative to the link_name frame, by default 0.0.
  • w_rot (float, optional) – The w orientation relative to the link_name frame, by default 1.0.
  • reference_frame (str, optional) – The frame in which the pose is expressed, by default world.
class panda_autograsp.moveit_collision_objects.Mesh(name, file_name, x_pos=0.0, y_pos=0.0, z_pos=0.0, x_rot=0.0, y_rot=0.0, z_rot=0.0, w_rot=1.0, reference_frame='world')[source]

Bases: object

Moveit mesh collision object class.

type

Collision object type.

Type:str
name

The name of the object.

Type:str
file_name

The location of the mesh file.

Type:str
x_pos

The x position in link_name frame.

Type:float
y_pos

The y position in link_name frame.

Type:float
z_pos

The z position in link_name frame.

Type:float
x_rot

The x orientation relative to the link_name frame.

Type:float
y_rot

The y orientation relative to the link_name frame.

Type:float
z_rot

The z orientation relative to the link_name frame.

Type:float
w_rot

The w orientation relative to the link_name frame.

Type:float
pose

The object pose.

Type:geometry_msgs.PoseStamped
__init__(name, file_name, x_pos=0.0, y_pos=0.0, z_pos=0.0, x_rot=0.0, y_rot=0.0, z_rot=0.0, w_rot=1.0, reference_frame='world')[source]
Parameters:
  • name (str) – The name of the object
  • file_name (str) – The location of the mesh file.
  • x_pos (float, optional) – The x position in link_name frame, by default 0.0.
  • y_pos (float, optional) – The y position in link_name frame, by default 0.0.
  • z_pos (float, optional) – The z position in link_name frame, by default 0.0.
  • x_rot (float, optional) – The x orientation relative to the link_name frame, by default 0.0.
  • y_rot (float, optional) – The y orientation relative to the link_name frame, by default 0.0.
  • z_rot (float, optional) – The z orientation relative to the link_name frame, by default 0.0.
  • w_rot (float, optional) – The w orientation relative to the link_name frame, by default 1.0.
  • reference_frame (str, optional) – The frame in which the pose is expressed, by default world.

panda_autograsp.moveit_planner_server_ros module

Module which sets up a number of services that can be used to control the Panda Emika Franka robot.

class panda_autograsp.moveit_planner_server_ros.MoveitPlannerServer(robot_description, args, move_group='panda_arm', move_group_end_effector_link='panda_gripper_center', move_group_gripper='hand', pose_reference_frame='panda_link0', planner='TRRTkConfigDefault', add_scene_collision_objects=True)[source]

Class used for controlling the Panda Emika Franka robot.

robot

The moveit robot commander.

Type:moveit_commander.RobotCommander
move_group

The main robot move group.

Type:moveit_commander.MoveGroupCommander
move_group_gripper

The gripper move group.

Type:moveit_commander.MoveGroupCommander
scene

The moveit scene commander.

Type:moveit_commander.PlanningSceneInterface
current_plan

The last computed plan of the main move group.

current_plan_gripper

The last computed plan of the gripper.

desired_pose

The main move group goal pose.

Type:list
desired_joint_values

The main move group target joint values.

Type:list
desired_gripper_joint_values

The gripper target joint values.

Type:list
__init__(robot_description, args, move_group='panda_arm', move_group_end_effector_link='panda_gripper_center', move_group_gripper='hand', pose_reference_frame='panda_link0', planner='TRRTkConfigDefault', add_scene_collision_objects=True)[source]

PandaPathPlannerService class initialization.

Parameters:
  • robot_description (str) – Where to find the URDF.
  • args (objects) – Roscpp args, passed on.
  • move_group (str) – Name of the pose planning reference frame, by default “panda_link0”.
  • move_group_end_effector_link (str) – Name of the end effector link.
  • move_group_gripper (str) – Name of the move group, by default “panda_arm_hand”.
  • pose_reference_frame (str) – Name of the planner reference frame.
  • planner (str, optional) – The Path planning algorithm, by default ‘TRRTkConfigDefault’.
  • add_scene_collision_objects (bool) – If true the collision objects specified in the moveit_scene_constraints.yaml file will be added to the scene.
plan_to_joint_service(req)[source]

Plan to a given joint position.

Parameters:req (panda_autograsp.msg.PlanToJoint) – The service request message containing the joint targets you want to plan to.
Returns:Boolean specifying whether the planning was successful.
Return type:Bool
plan_to_point_service(req)[source]

Plan to a given pose.

Parameters:req (panda_autograsp.msg.PlanToPoint) – The service request message containing the pose you want to plan to.
Returns:Boolean specifying whether the planning was successful.
Return type:bool
plan_cartesian_path_service(req)[source]

Plan to a given cartesian path.

Parameters:req (panda_autograsp.msg.PlanToPath) – The service request message containing the path you want to plan to.
Returns:Boolean specifying whether the planning was successful.
Return type:bool
plan_random_pose_service(req)[source]

Plan to a random pose goal.

Parameters:req (panda_autograsp.msg.PlanToRandomPoint) – Empty service request.
Returns:Returns a bool to specify whether the plan was executed successfully.
Return type:bool
plan_random_joint_service(req)[source]

Plan to a random joint goal.

Parameters:req (panda_autograsp.msg.PlanToRandomJoint) – Empty service request.
Returns:Returns a bool to specify whether the plan was executed successfully.
Return type:bool
plan_random_cartesian_path_service(req)[source]

Plan to a random cartesian path.

Parameters:req (panda_autograsp.msg.PlanToRandomPath) – Empty service request.
Returns:Returns a bool to specify whether the plan was executed successfully.
Return type:bool
visualize_plan_service(req)[source]

Visualize the plan that has been computed by the other plan services.

Parameters:req (panda_autograsp.msg.VisualizePlan) – Empty service request.
Returns:Returns a bool to specify whether the plan was executed successfully.
Return type:bool
execute_plan_service(req)[source]

Execute the plan that has been computed for the main move group by the other plan services.

Parameters:req (panda_autograsp.msg.ExecutePlan) – Empty service request.
Returns:Returns a bool to specify whether the plan was executed successfully.
Return type:bool
plan_gripper_service(req)[source]

Compute plan for the currently set gripper target joint values.

Parameters:req (panda_autograsp.msg.PlanGripper.) – Empty service request.
Returns:Returns a bool to specify whether the plan was executed successfully.
Return type:bool
execute_gripper_plan_service(req)[source]

Execute previously planned gripper plan.

Parameters:req (panda_autograsp.msg.ExecuteGripperPlan.) – Empty service request.
Returns:Returns a bool to specify whether the plan was executed successfully.
Return type:bool
open_gripper_service(req)[source]

Open the gripper.

Parameters:req (panda_autograsp.msg.OpenGripper.) – Empty service request.
Returns:Returns a bool to specify whether the plan was executed successfully.
Return type:bool
close_gripper_service(req)[source]

Close the gripper.

Parameters:req (panda_autograsp.msg.CloseGripper.) – Empty service request.
Returns:Returns a bool to specify whether the plan was executed successfully.
Return type:bool
set_gripper_open_service(req)[source]

Set gripper joint targets values to open.

Parameters:req (panda_autograsp.msg.SetGripperOpen.) – Empty service request.
Returns:Returns a bool to specify whether the plan was executed successfully.
Return type:bool
set_gripper_closed_service(req)[source]

Set gripper joint target values to closed.

Parameters:req (panda_autograsp.msg.SetGripperClosed.) – Empty service request.
Returns:Returns a bool to specify whether the plan was executed successfully.
Return type:bool
set_gripper_width_service(req)[source]

Set gripper joint target values to a given value.

Parameters:req (panda_autograsp.msg.SetGripperWidth.) – This message specifies the gripper width.
Returns:Returns a bool to specify whether the plan was executed successfully.
Return type:bool

panda_autograsp.panda_autograsp_server_ros module

Module that sets up a number of services that enable the panda_autograsp_cli command line interface (CLI) to communicate with the components of the panda_autograps solution.

class panda_autograsp.panda_autograsp_server_ros.PandaAutograspServer(pose_calib_method='aruco_board', gazebo=False, bounding_box_enabled=False)[source]

Class used to create and call all the panda_autograsp components.

rvec

The rotation vector of the camera/world calibration.

Type:list
tvec

The translation vector of the camera/world calibration.

Type:list
__init__(pose_calib_method='aruco_board', gazebo=False, bounding_box_enabled=False)[source]
Parameters:
  • pose_calib_method (str, optional) – Calibration pattern type., by default read from main_config.yaml.
  • gazebo (bool, optional) – Specifies whether you want to use a gazebo simulation, by default false.
  • bounding_box_enabled (bool, optional) – Specifies whether you want to use a bounding box for the grasp detection.
get_pose_callback(pose_msg)[source]

Callback function of the ‘gqcnn_graps/pose’ subscriber. This function updates the self.pose_msg member variable.

Parameters:pose_msg (geometry_msgs.PosedStamed) – Grasp pose msgs.
msg_filter_callback(color_image, color_image_rect, depth_image_rect, camera_info_hd, camera_info_qhd, camera_info_sd)[source]

Callback function of the message filter. This message filter subscribed to a number of camera topics which are required by the panda_autograsp solution. :param color_image: The color image. :type color_image: sensor_msgs.msg.Image :param color_image_rect: The rectified color image. :type color_image_rect: sensor_msgs.msg.Image :param depth_image_rect: The depth image. :type depth_image_rect: sensor_msgs.msg.Image :param camera_info_hd: The HD camera info topic. :type camera_info_hd: sensor_msgs.msg.CameraInfo :param camera_info_qhd: The QHD camera topic. :type camera_info_qhd: sensor_msgs.msg.CameraInfo :param camera_info_sd: The SD camera topic. :type camera_info_sd: sensor_msgs.msg.CameraInfo

compute_grasp_service(req)[source]

This service is used for computing a vallid grasp out of the sensor data. This is done by calling the main grasp computation service of the grasp_planner_server.py module with the sensor data as its input.

Parameters:req (panda_autograsp.msg.ComputeGrasp) – Empty service request.
Returns:Returns a bool to specify whether the plan was executed successfully.
Return type:bool
plan_grasp_service(req)[source]

This service can be used to plan for the by the compute_grasp_service() computed grasp pose.

Parameters:req (panda_autograsp.msg.PlanGrasp) – Empty service request.
Returns:Returns a bool to specify whether the plan was executed successfully.
Return type:bool
plan_place_service(req)[source]

This service computes the movement plan for placing the object at the desired goal position. The place goal position can be changed by modifying the cfg/main_config.yaml document.

Parameters:req (panda_autograsp.msg.PlanPlace) – Empty service request.
Returns:Returns a bool to specify whether the plan was executed successfully.
Return type:bool
visualize_grasp_service(req)[source]

This service can be used to visualize the planned grasp.

Parameters:req (panda_autograsp.msg.VizualizeGrasp) – Empty service request.
Returns:Returns a bool to specify whether the plan was executed successfully.
Return type:bool
execute_grasp_service(req)[source]

This service is used to execute the computed grasp.

Parameters:req (panda_autograsp.msg.ExecuteGrasp) – Empty service request.
Returns:Returns a bool to specify whether the plan was executed successfully.
Return type:bool
calibrate_sensor_service(req)[source]

This service can be used to perform the sensor/world calibration. To do this you need to place a chessboard/aruco board in the bottom left corner of the robot table. You have to define which calibration pattern you use in the cfg/main_config.yaml file. After a successful camera/world transformation matrix is computed this matrix is send to the tf2_broadcaster module and the sensor frame position is updated.

Parameters:req (panda_autograsp.msg.ExecuteGrasp) – Empty service request.
Returns:Returns a bool to specify whether the plan was executed successfully.
Return type:bool
aruco_board_pose_estimation()[source]

Function that performs the camera/world calibration by using a Aruco board as a reference.

Returns:
  • retval (bool) – Calibration success bool.
  • rvec (list) – Rotation vector.
  • tvec (list) – Translation vector.
chessboard_pose_estimation()[source]

Function that performs the camera/world calibration by using a chessboard as a reference.

Returns:
  • retval (bool) – Calibration success bool.
  • rvec (list) – Rotation vector.
  • tvec (list) – Translation vector.
broadcast_camera_frame(calib_type='aruco_board')[source]

Send the sensor pose we acquired from the calibration to the tf2_broadcaster so that it can broadcast the sensor camera frame.

Parameters:calib_type (str, optional) – The calibration pattern you want to use, by default “aruco_board”

panda_autograsp.tf2_broadcaster_ros module

Module that can be used to broadcasts a number of tf2 frames and ensures these frames can be updated using a dynamic reconfigure server.

panda_autograsp.tf2_broadcaster_ros.get_dynamic_param(parameter_name)[source]

This function retrieves a parameter from the parameter server just like the rospy.get_param() function. Additionally to the rospy.get_param() function, if a parameter is not found on the parameter server it also tries to retrieve a value for the parameter using the CalibFramesConfig.defaults dict.

Returns:
class panda_autograsp.tf2_broadcaster_ros.Tf2Broadcaster[source]

Tf2 broadcaster class.

calib_frame_x_pos

Calibration frame x position [m] (Relative to the ‘panda_link0` frame).

Type:float
calib_frame_y_pos

Calibration frame y position [m] (Relative to the ‘panda_link0` frame).

Type:float
calib_frame_z_pos

Calibration frame z position [m] (Relative to the ‘panda_link0` frame).

Type:float
calib_frame_yaw

Calibration frame yaw orientation [rad] (Relative to the ‘panda_link0` frame).

Type:float
calib_frame_pitch

Calibration frame pitch orientation [rad] (Relative to the ‘panda_link0` frame).

Type:float
calib_frame_roll

Calibration frame roll orientation [rad] (Relative to the ‘panda_link0` frame).

Type:float
sensor_frame_x_pos

Sensor frame x position [m] (Relative to the ‘calib_frame` frame).

Type:float
sensor_frame_y_pos

Sensor frame y position [m] (Relative to the ‘calib_frame` frame).

Type:float
sensor_frame_z_pos

Sensor frame z position [m] (Relative to the ‘calib_frame` frame).

Type:float
sensor_frame_q1
Sensor frame x quaternion orientation [rad] (Relative to the ‘calib_frame`
frame).
Type:float
sensor_frame_q2
Sensor frame y quaternion orientation [rad] (Relative to the ‘calib_frame`
frame).
Type:float
sensor_frame_q3
Sensor frame z quaternion orientation [rad] (Relative to the ‘calib_frame`
frame).
Type:float
sensor_frame_q4
Sensor frame w quaternion orientation [rad] (Relative to the ‘calib_frame`
frame).
Type:float
sensor_frame_yaw

Sensor frame yaw orientation [rad] (Relative to the ‘panda_link0` frame).

Type:float
sensor_frame_pitch

Sensor frame pitch orientation [rad] (Relative to the ‘panda_link0` frame).

Type:float
sensor_frame_roll

Sensor frame roll orientation [rad] (Relative to the ‘panda_link0` frame).

Type:float
conf

Dynamic reconfigure server configuration dictionary.

Type:dict
set_sensor_pose_service(sensor_pose)[source]

Give sensor pose of the calibration to the tf2 broadcaster.

Parameters:sensor_pose (dict) – Dictionary containing the pose of the sensor {x, y, z,q1, q2, q3, q4, yaw, pitch, roll}
dync_reconf_callback(config, level)[source]

Dynamic reconfigure callback function. This callback function updates the values of the dynamic reconfigure server.

Parameters:
  • config (dict) – Dictionary containing the dynamically reconfigured parameters.
  • level (int) – A bitmask which will later be passed to the dynamic reconfigure callback. When the callback is called all of the level values for parameters that have been changed are added together and the resulting value is passed to the callback.
tf2_broadcaster_callback(event=None)[source]

TF2 broadcaster callback function. This callback function broadcasts the tf2 frames.

Parameters:event (rospy.timer.TimerEvent, optional) – Structure passed in provides you timing information that can be useful when debugging or profiling, by default None
shutdown_hook()[source]

This functions gets called when the node is shutdown. This function makes sure the previous calibration results are save to the calibration file before the node is shutdown.

Module contents