panda_autograsp.tf2_broadcaster_ros¶
Module that can be used to broadcasts a number of tf2 frames and ensures these frames can be updated using a dynamic reconfigure server.
Functions
get_dynamic_param (parameter_name) |
This function retrieves a parameter from the parameter server just like the rospy.get_param() function. |
Classes
Tf2Broadcaster () |
Tf2 broadcaster class. |
-
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 therospy.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_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
-
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.
- config (
-
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
-