The operator_node
package provides tools for mapping raw interface commands to operator signals.
Recieves joy messages from a joy_node and republishes at a given sampling frequency. Sometimes I have noticed the sampling frequency of a joy_node does not always match the observed frequency (the difference is typically fairly small but significant).
-
~hz
(int, default: 100)Sampling frequency.
-
joy_in
(sensor_msgs/Joy)Raw signals from interface driver.
-
joy_out
(sensor_msgs/Joy)Raw signals from interface driver published at given sampling frequency.
This node collects a log of the previous N
operator signals and
publishes this including timestamps as a flattened std_msgs/Float64MultiArray
message. The window duration is given in time (seconds).
You can think of the log as being a (1+Nd)
-by-N
array that has been
flattened by columns. N
is the number of signals in the current
buffer. Nd
is the number of dimensions of the operator signal, and
the 1
is for the time stamp.
-
~window_duration
(float)The operator signals recieved within this window of time will be published on each topic.
-
operator_node/signal
(std_msgs/Float64MultiArray)Operator signals.
-
operator_node/window
(std_msgs/Float64MultiArray)A list of operator signals recieved in the previous window of time. Note, a helper function in Python is provided named
reconstruct_interface_log_msg
, see example:import rospy import operator_node from std_msgs.msg import Float64MultiArray Nd = 2 # number of dims for operator signal def callback(msg): t, h = operator_node.parser.reconstruct_interface_log_msg(msg, Nd) print("-"*70) print(f"{t = }") print(f"{h = }") rospy.init_node('test') rospy.Subscriber('operator_node/window', Float64MultiArray, callback) rospy.spin()
Scale the interface axes but ensure isometric.
-
~config/axes_idx
(list[int])Indicices of the axes to be used to generate operator signal.
-
~config/scale
(float, min: 0.0, max: inf, default: 1.0)Maximum operator signal magnitude.
-
~start_on_init
(bool, default: False)Start the subscriber on initialization. Otherwise use a service to toggle subscriber on/off.
-
joy
(sensor_msgs/Joy)Interface signals.
-
operator_node/signal
(std_msgs/Float64MultiArray)Operator signals.
-
operator_node/toggle
(std_srvs/SetBool)Toggle the operator node on/off.
Simply scale each interface axes.
-
~config/axes_idx
(list[int])Indicices of the axes to be used to generate operator signal.
-
~config/scale
(either: list[float], float, default: 1.0)Maximum operator signal magnitude along each dimension.
-
~start_on_init
(bool, default: False)Start the subscriber on initialization. Otherwise use a service to toggle subscriber on/off.
-
joy
(sensor_msgs/Joy)Interface signals.
-
operator_node/signal
(std_msgs/Float64MultiArray)Operator signals.
-
operator_node/toggle
(std_srvs/SetBool)Toggle the operator node on/off.
Map keyboard events to sensor_msgs/Joy
messages.
-
~config
(dict)Configuration file, see example in
configs/
. -
~hz
(int, default: 100)Sampling frequency.
-
keyboard/keyup
(keyboard/Key)Keyboard key-up events.
-
keyboard/keydown
(keyboard/Key)Keyboard key-down events.
-
joy
(sensor_msgs/Joy)Joy messages representing keyboard events.