command_run.c
Go to the documentation of this file.
00001 // Copyright (c) 2010-2016 The YP-Spur Authors, except where otherwise indicated.
00002 //
00003 // Permission is hereby granted, free of charge, to any person obtaining a copy
00004 // of this software and associated documentation files (the "Software"), to
00005 // deal in the Software without restriction, including without limitation the
00006 // rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
00007 // sell copies of the Software, and to permit persons to whom the Software is
00008 // furnished to do so, subject to the following conditions:
00009 //
00010 // The above copyright notice and this permission notice shall be included in
00011 // all copies or substantial portions of the Software.
00012 //
00013 // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
00014 // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
00015 // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL
00016 // THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
00017 // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
00018 // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
00019 // SOFTWARE.
00020 
00021 #include <math.h>
00022 #include <stdio.h>
00023 #include <strings.h>
00024 #include <unistd.h>
00025 
00026 #include <fcntl.h>
00027 #include <sys/time.h>
00028 #include <sys/types.h>
00029 #include <time.h>
00030 
00031 #ifdef HAVE_CONFIG_H
00032 #include <config.h>
00033 #endif  // HAVE_CONFIG_H
00034 
00035 /* ボディパラメータ */
00036 #include <shvel-param.h>
00037 
00038 /* yp-spur用 */
00039 #include <serial.h>
00040 #include <param.h>
00041 #include <control.h>
00042 #include <command.h>
00043 
00044 /* ライブラリ用 */
00045 #include <ypspur.h>
00046 #include <cartesian2d.h>
00047 
00048 void line_com(int cs, double *data, SpurUserParamsPtr spur)
00049 {
00050   double x, y, theta;
00051 
00052   x = data[0];
00053   y = data[1];
00054   theta = data[2];
00055 
00056   cstrans_xy(cs, CS_SP, &x, &y, &theta);
00057 
00058   spur->x = x;
00059   spur->y = y;
00060   spur->theta = theta;
00061   spur->run_mode = RUN_LINEFOLLOW;
00062 }
00063 
00064 void stop_line_com(int cs, double *data, SpurUserParamsPtr spur)
00065 {
00066   double x, y, theta;
00067 
00068   x = data[0];
00069   y = data[1];
00070   theta = data[2];
00071 
00072   cstrans_xy(cs, CS_SP, &x, &y, &theta);
00073 
00074   spur->x = x;
00075   spur->y = y;
00076   spur->theta = theta;
00077   spur->run_mode = RUN_STOP_LINE;
00078 }
00079 
00080 void circle_com(int cs, double *data, SpurUserParamsPtr spur)
00081 {
00082   double x, y, theta;
00083 
00084   x = data[0];
00085   y = data[1];
00086   theta = 0;
00087 
00088   cstrans_xy(cs, CS_SP, &x, &y, &theta);
00089 
00090   spur->x = x;
00091   spur->y = y;
00092   spur->radius = data[2];
00093   spur->run_mode = RUN_CIRCLEFOLLOW;
00094 }
00095 
00096 void spin_com(int cs, double *data, SpurUserParamsPtr spur)
00097 {
00098   double x, y, theta;
00099 
00100   x = 0;
00101   y = 0;
00102   theta = data[0];
00103 
00104   cstrans_xy(cs, CS_SP, &x, &y, &theta);
00105 
00106   spur->theta = theta;
00107   spur->run_mode = RUN_SPIN;
00108 }
00109 
00110 void orient_com(int cs, double *data, SpurUserParamsPtr spur)
00111 {
00112   double x, y, theta;
00113 
00114   x = 0;
00115   y = 0;
00116   theta = data[0];
00117 
00118   cstrans_xy(cs, CS_SP, &x, &y, &theta);
00119 
00120   spur->theta = theta;
00121   spur->run_mode = RUN_ORIENT;
00122 }
00123 
00124 void stop_com(double *data, SpurUserParamsPtr spur)
00125 {
00126   spur->run_mode = RUN_STOP;
00127 }
00128 
00129 void free_com(double *data, SpurUserParamsPtr spur)
00130 {
00131   spur->run_mode = RUN_FREE;
00132 }
00133 
00134 void openfree_com(double *data, SpurUserParamsPtr spur)
00135 {
00136   spur->run_mode = RUN_OPENFREE;
00137 }
00138 
00139 void vel_com(double *data, SpurUserParamsPtr spur)
00140 {
00141   spur->vref = data[0];
00142   spur->wref = data[1];
00143   spur->run_mode = RUN_VEL;
00144 }
00145 
00146 void wheel_vel_com(double *data, SpurUserParamsPtr spur)
00147 {
00148   spur->wvelref[0] = data[0];
00149   spur->wvelref[1] = data[1];
00150   spur->run_mode = RUN_WHEEL_VEL;
00151 }
00152 
00153 void wheel_angle_com(double *data, SpurUserParamsPtr spur)
00154 {
00155   double r, l;
00156 
00157   r = data[0];
00158   l = data[1];
00159 
00160   if (isset_p(YP_PARAM_MIN_WHEEL_ANGLE, MOTOR_RIGHT))
00161   {
00162     if (r < p(YP_PARAM_MIN_WHEEL_ANGLE, MOTOR_RIGHT))
00163       r = p(YP_PARAM_MIN_WHEEL_ANGLE, MOTOR_RIGHT);
00164   }
00165   if (isset_p(YP_PARAM_MIN_WHEEL_ANGLE, MOTOR_LEFT))
00166   {
00167     if (l < p(YP_PARAM_MIN_WHEEL_ANGLE, MOTOR_LEFT))
00168       l = p(YP_PARAM_MIN_WHEEL_ANGLE, MOTOR_LEFT);
00169   }
00170   if (isset_p(YP_PARAM_MAX_WHEEL_ANGLE, MOTOR_RIGHT))
00171   {
00172     if (r > p(YP_PARAM_MAX_WHEEL_ANGLE, MOTOR_RIGHT))
00173       r = p(YP_PARAM_MAX_WHEEL_ANGLE, MOTOR_RIGHT);
00174   }
00175   if (isset_p(YP_PARAM_MAX_WHEEL_ANGLE, MOTOR_LEFT))
00176   {
00177     if (l > p(YP_PARAM_MAX_WHEEL_ANGLE, MOTOR_LEFT))
00178       l = p(YP_PARAM_MAX_WHEEL_ANGLE, MOTOR_LEFT);
00179   }
00180 
00181   spur->wheel_angle[1] = l;
00182   spur->wheel_angle[0] = r;
00183   spur->run_mode = RUN_WHEEL_ANGLE;
00184 }


yp-spur
Author(s):
autogenerated on Fri May 10 2019 02:52:19