25 #ifndef _PLUGINS_ROBOTINO_ACT_THREAD_H_
26 #define _PLUGINS_ROBOTINO_ACT_THREAD_H_
28 #include <aspect/blackboard.h>
29 #include <aspect/blocked_timing.h>
30 #include <aspect/clock.h>
31 #include <aspect/configurable.h>
32 #include <aspect/logging.h>
33 #include <core/threading/thread.h>
35 # include <aspect/tf.h>
42 class GripperInterface;
75 typedef enum { ODOM_COPY, ODOM_CALC } OdometryMode;
77 void publish_odometry();
78 void publish_gripper();
83 unsigned int last_seqnum_;
87 unsigned int imu_if_nochange_loops_;
88 bool imu_if_writer_warning_printed_;
89 bool imu_if_invquat_warning_printed_;
90 bool imu_if_changed_warning_printed_;
95 float cfg_deadman_threshold_;
96 float cfg_odom_time_offset_;
97 bool cfg_gripper_enabled_;
98 std::string cfg_odom_frame_;
99 std::string cfg_base_frame_;
100 OdometryMode cfg_odom_mode_;
101 unsigned int cfg_imu_deadman_loops_;
102 float cfg_odom_corr_phi_;
103 float cfg_odom_corr_trans_;
104 bool cfg_bumper_estop_enabled_;
108 float cfg_trans_accel_;
109 float cfg_trans_decel_;
110 float cfg_rot_accel_;
111 float cfg_rot_decel_;
114 bool cfg_publish_transform_;
122 float odom_gyro_origin_;
128 std::string last_transrot_sender_;