Go to the documentation of this file.
   34 #include <sys/types.h> 
   39 #endif  // HAVE_CONFIG_H 
   75     switch (
spur->wheel_mode[i])
 
   85         switch (
spur->wheel_mode[i])
 
   89                 podm->
wang[i] - 
spur->wheel_angle[i],
 
   92                 spur->wheel_accel[i]);
 
   96                 podm->
wang[i] - 
spur->wheel_angle[i],
 
  100                 spur->wheel_vel_end[i]);
 
  105         ref = 
spur->wvelref[i];
 
  115         spur->wheel_vel_smooth[i] = ref;
 
  118           if ((
spur->wheel_vel_end[i] > 0.0 &&
 
  119                spur->wheel_angle[i] > podm->
wang[i] &&
 
  121               (
spur->wheel_vel_end[i] < 0.0 &&
 
  122                spur->wheel_angle[i] < podm->
wang[i] &&
 
  126             spur->wvelref[i] = 
spur->wheel_vel_end[i];
 
  142   spur->run_mode_cnt++;
 
  150     int force_send_control_mode = 0;
 
  154       if (
spur->run_mode_cnt % cnt_max == i % cnt_max)
 
  155         force_send_control_mode = 1;
 
  158     if (
spur->wheel_mode[i] != 
spur->wheel_mode_prev[i] || force_send_control_mode)
 
  160       switch (
spur->wheel_mode[i])
 
  176     spur->wheel_mode_prev[i] = 
spur->wheel_mode[i];
 
  178     switch (
spur->wheel_mode[i])
 
  190           v = (double)(16 * 
spur->wheel_vel_smooth[i] *
 
  197           v = (double)(
spur->wheel_vel_smooth[i] *
 
  219     if (
spur->torque[i] != 
spur->torque_prev[i])
 
  225     spur->torque_prev[i] = 
spur->torque[i];
 
  237     spur->wheel_vel_smooth[i] = podm->
wvel[i];
 
  239   spur->vref_smooth = podm->
v;
 
  240   spur->wref_smooth = podm->
w;
 
  260       spur->wheel_vel_smooth[i] = 0;
 
  328       torque[i] += 
spur->torque[i];
 
  360   if (v > fabs(
spur->v))
 
  364   else if (v < -fabs(
spur->v))
 
  373   if (v > 
spur->vref_smooth + dv)
 
  375     v = 
spur->vref_smooth + dv;
 
  377   else if (v < spur->vref_smooth - dv)
 
  379     v = 
spur->vref_smooth - dv;
 
  386   if (w > fabs(
spur->w))
 
  390   else if (w < -fabs(
spur->w))
 
  399   if (w > 
spur->wref_smooth + dw)
 
  401     w = 
spur->wref_smooth + dw;
 
  403   else if (w < spur->wref_smooth - dw)
 
  405     w = 
spur->wref_smooth - dw;
 
  412   if (
spur->wref_smooth != 0)
 
  432   spur->vref_smooth = v;
 
  433   spur->wref_smooth = w;
 
  472 #if defined(HAVE_LIBRT)  // clock_nanosleepが利用可能 
  473   struct timespec request;
 
  475   if (clock_gettime(CLOCK_MONOTONIC, &request) == -1)
 
  483     request.tv_sec += request.tv_nsec / 1000000000;
 
  484     request.tv_nsec = request.tv_nsec % 1000000000;
 
  486     clock_nanosleep(CLOCK_MONOTONIC, TIMER_ABSTIME, &request, 0);
 
  491     pthread_testcancel();
 
  504     pthread_testcancel();
 
  506 #endif  // defined(HAVE_LIBRT) 
  507   pthread_cleanup_pop(1);
 
  513   static double before_time = 0;
 
  521   spur->control_dt = now_time - before_time;
 
  523   before_time = now_time;
 
  524   if (before_time == 0)
 
  528   pthread_mutex_lock(&
spur->mutex);
 
  543     spur_freeze.
vref = 0;
 
  544     spur_freeze.
wref = 0;
 
  550         spur_freeze.
torque[i] = 0;
 
  595         torque_ref[i] += 
spur->grav_torque[i];
 
  600     switch (
spur->run_mode)
 
  647     switch (
spur->run_mode)
 
  667   pthread_mutex_unlock(&
spur->mutex);
 
  673   if (pthread_create(thread, NULL, (
void *)
control_loop, NULL) != 0)
 
  
double wheel_vel_smooth[YP_PARAM_MAX_MOTOR_NUM]
void apply_motor_speed(SpurUserParamsPtr spur)
@ YP_PARAM_MAX_CENTRIFUGAL_ACC
int parameter_set(char param, char id, long long int value64)
double wang[YP_PARAM_MAX_MOTOR_NUM]
@ YP_PARAM_CONTROL_MODE_RESEND
void update_ref_speed(SpurUserParamsPtr spur)
int motor_control(SpurUserParamsPtr spur)
MotorControlMode wheel_mode_prev[YP_PARAM_MAX_MOTOR_NUM]
void cstrans_odometry(YPSpur_cs cs, OdometryPtr dst_odm)
double timeoptimal_servo(double err, double vel_max, double vel, double acc)
double spin(OdometryPtr odm, SpurUserParamsPtr spur)
int isset_p(YPSpur_param id, enum motor_id motor)
void wheel_vel(OdometryPtr odm, SpurUserParamsPtr spur)
void run_control(Odometry odometry, SpurUserParamsPtr spur)
int state(YPSpur_state id)
SpurUserParamsPtr get_spur_user_param_ptr()
double gravity_compensation(OdometryPtr odm, SpurUserParamsPtr spur)
double circle_follow(OdometryPtr odm, SpurUserParamsPtr spur)
void apply_motor_torque(SpurUserParamsPtr spur)
double line_follow(OdometryPtr odm, SpurUserParamsPtr spur)
OdometryPtr get_odometry_ptr()
@ MOTOR_CONTROL_ANGLE_VEL
void wheel_angle(OdometryPtr odm, SpurUserParamsPtr spur)
#define YP_PARAM_MAX_MOTOR_NUM
double torque[YP_PARAM_MAX_MOTOR_NUM]
double timeoptimal_servo2(double err, double vel_max, double vel, double acc, double vel_end)
double wvel[YP_PARAM_MAX_MOTOR_NUM]
void yprintf(ParamOutputLv level, const char *format,...)
double orient(OdometryPtr odm, SpurUserParamsPtr spur)
void coordinate_synchronize(Odometry *odm, SpurUserParamsPtr spur)
int stop_line(OdometryPtr odm, SpurUserParamsPtr spur)
void robot_speed(SpurUserParamsPtr spur)
ParametersPtr get_param_ptr()
@ YP_PARAM_VEHICLE_CONTROL
double torque_prev[YP_PARAM_MAX_MOTOR_NUM]
void init_control_thread(pthread_t *thread)
int motor_enable[YP_PARAM_MAX_MOTOR_NUM]
double p(YPSpur_param id, enum motor_id motor)
void odometry(OdometryPtr xp, short *cnt, short *pwm, double dt, double time)
void wheel_torque(OdometryPtr odm, SpurUserParamsPtr spur, double *torque)
int robot_speed_smooth(SpurUserParamsPtr spur)
void control_loop_cleanup(void *data)
int option(ParamOptions option)
yp-spur
Author(s): 
autogenerated on Fri Oct 20 2023 03:02:42