pycram.ros_utils.force_torque_sensor#
Classes#
Simulated force-torque sensor for a joint with a given name. |
|
Monitor a force-torque sensor of a supported robot and save relevant data. |
Module Contents#
- class pycram.ros_utils.force_torque_sensor.ForceTorqueSensorSimulated(joint_name, fts_topic='/pycram/fts', interval=0.1)#
Simulated force-torque sensor for a joint with a given name. Reads simulated forces and torques at that joint from world and publishes geometry_msgs/Wrench messages to the given topic.
- world#
- fts_joint_idx = None#
- joint_name#
- fts_pub#
- interval = 0.1#
- kill_event#
- thread#
- _publish() None#
Continuously publishes the force-torque values for the simulated joint. Values are published as long as the kill_event is not set.
- _stop_publishing() None#
Sets the kill_event and therefore terminates the Thread publishing the force-torque values as well as join the threads.
- class pycram.ros_utils.force_torque_sensor.ForceTorqueSensor(robot_name, filter_config=FilterConfig.butterworth, filter_order=4, custom_topic=None, debug=False)#
Monitor a force-torque sensor of a supported robot and save relevant data.
Apply a specified filter and save this data as well. Default filter is the low pass filter ‘Butterworth’
Can also calculate the derivative of (un-)filtered data
- Parameters:
robot_name – Name of the robot
filter_config – Desired filter (default: Butterworth)
filter_order – Order of the filter. Declares the number of elements that delay the sampling
custom_topic – Declare a custom topic if the default topics do not fit
- filtered = 'filtered'#
- unfiltered = 'unfiltered'#
- robot_name#
- filter_config#
- filter#
- debug = False#
- wrench_topic_name = None#
- force_torque_subscriber = None#
- init_data = True#
- whole_data = None#
- prev_values = None#
- order = 4#
- _setup()#
- _get_robot_parameters()#
- _get_rospy_data(data_compensated: geometry_msgs.msg.WrenchStamped)#
- _get_filter(order=4, cutoff=10, fs=60)#
- _filter_data(current_wrench_data: geometry_msgs.msg.WrenchStamped) geometry_msgs.msg.WrenchStamped#
- subscribe()#
Subscribe to the specified wrench topic.
This will automatically be called on setup. Only use this if you already unsubscribed before.
- unsubscribe()#
Unsubscribe from the specified topic
- get_last_value(is_filtered=True) geometry_msgs.msg.WrenchStamped#
Get the most current data values.
- Parameters:
is_filtered – Decides about using filtered or raw data
- Returns:
A list containing the most current values (newest are first)
- get_derivative(is_filtered=True) geometry_msgs.msg.WrenchStamped#
Calculate the derivative of current data.
- Parameters:
is_filtered – Decides about using filtered or raw data.
- Returns:
The derivative as a WrenchStamped object. Returns a zeroed derivative if only one data point exists.
- human_touch_monitoring()#