45 double turning_adaptation,
51 bool drive_backwards) :
52 epos2_left_(drive_backwards ? 0x01 : 0x02),
53 epos2_right_(drive_backwards ? 0x02 : 0x01),
55 wheel_radius_(wheel_radius),
56 axis_length_(axis_length),
57 turning_adaptation_(turning_adaptation),
58 gear_ratio_(gear_ratio),
59 max_vel_l_(max_vel_l),
60 max_vel_r_(max_vel_r),
61 max_acc_l_(max_acc_l),
112 epos2_right_.setTargetVelocity(-1.0 * _v_r_soll / ( 2.0 * M_PI * wheel_radius_) * 60.0 * gear_ratio_);
117 static double x = 0.0;
118 static double y = 0.0;
119 static double theta = 0.0;
120 static long enc_left_last =
epos2_left_.readEncoderCounter();
121 static long enc_right_last =
epos2_right_.readEncoderCounter();
127 long wheel_l = enc_left - enc_left_last;
128 long wheel_r = enc_right - enc_right_last;
131 if((abs(enc_left) > 10000) && (std::signbit(enc_left) != std::signbit(enc_left_last)))
133 if(std::signbit(enc_left))
134 wheel_l = std::numeric_limits<int32_t>::max() - enc_left_last - std::numeric_limits<int32_t>::min() + enc_left;
136 wheel_l = std::numeric_limits<int32_t>::max() - enc_left - std::numeric_limits<int32_t>::min() + enc_left_last;
139 if((abs(enc_right) > 10000) && (std::signbit(enc_right) != std::signbit(enc_right_last)))
141 if(std::signbit(enc_right))
142 wheel_r = std::numeric_limits<int32_t>::max() - enc_right_last - std::numeric_limits<int32_t>::min() + enc_right;
144 wheel_r = std::numeric_limits<int32_t>::max() - enc_right - std::numeric_limits<int32_t>::min() + enc_right_last;
147 enc_left_last = enc_left;
148 enc_right_last = enc_right;
150 double wheel_L = 2.0 * M_PI *
wheel_radius_ * wheel_l / enc_per_turn_left;
151 double wheel_R = -2.0 * M_PI *
wheel_radius_ * wheel_r / enc_per_turn_right;
154 double hypothenuse = 0.5 * (wheel_L + wheel_R);
156 x += hypothenuse * cos(theta + dtheta * 0.5);
157 y += hypothenuse * sin(theta + dtheta * 0.5);
167 double v_x = (v_left + v_right) * 0.5;
170 double wheelpos_l = 2.0 * M_PI * (enc_left % enc_per_turn_left) / enc_per_turn_left;
171 if (wheelpos_l > M_PI)
172 wheelpos_l -= 2.0 * M_PI;
173 if (wheelpos_l < -M_PI)
174 wheelpos_l += 2.0 * M_PI;
176 double wheelpos_r = 2.0 * M_PI * (enc_right % enc_per_turn_right) / enc_per_turn_right;
177 if (wheelpos_r > M_PI)
178 wheelpos_r -= 2.0 * M_PI;
179 if (wheelpos_r < -M_PI)
180 wheelpos_r += 2.0 * M_PI;
TFSIMD_FORCE_INLINE const tfScalar & y() const
virtual void send_odometry(double x, double y, double theta, double v_x, double v_theta, double wheelpos_l, double wheelpos_r)=0
TFSIMD_FORCE_INLINE const tfScalar & x() const
double turning_adaptation_
Volksbot(Comm &comm, double wheel_radius, double axis_length, double turning_adaptation, int gear_ratio, int max_vel_l, int max_vel_r, int max_acc_l, int max_acc_r, bool drive_backwards)
void set_wheel_speed(double _v_l_soll, double _v_r_soll)