ypspur-md.h
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 #ifndef YPSPUR_MD_H
00022 #define YPSPUR_MD_H
00023 
00024 #include <ypparam.h>
00025 
00026 #ifdef __cplusplus
00027 extern "C" {
00028 #endif  // __cplusplus
00029 
00030 #define Spur_md_init(dev) YPSpur_md_init(dev)
00031 #define Spur_md_initex(dev, msq) YPSpur_md_initex(dev, msq)
00032 #define Spur_md_init_socket(dev, ip, port) YPSpur_md_init_socket(dev, ip, port)
00033 #define Spur_md_stop(dev) YPSpur_md_stop(dev)
00034 #define Spur_md_free(dev) YPSpur_md_free(dev)
00035 
00036 #define Spur_md_freeze(dev) YPSpur_md_freeze(dev)
00037 #define Spur_md_isfreeze(dev) YPSpur_md_isfreeze(dev)
00038 #define Spur_md_unfreeze(dev) YPSpur_md_unfreeze(dev)
00039 
00040 #define Spur_md_line_GL(dev, x, y, th) YPSpur_md_line(dev, CS_GL, x, y, th)
00041 #define Spur_md_line_LC(dev, x, y, th) YPSpur_md_line(dev, CS_LC, x, y, th)
00042 #define Spur_md_line_FS(dev, x, y, th) YPSpur_md_line(dev, CS_FS, x, y, th)
00043 #define Spur_md_line_BS(dev, x, y, th) YPSpur_md_line(dev, CS_BS, x, y, th)
00044 #define Spur_md_line_BL(dev, x, y, th) YPSpur_md_line(dev, CS_BL, x, y, th)
00045 
00046 #define Spur_md_stop_line_GL(dev, x, y, th) YPSpur_md_stop_line(dev, CS_GL, x, y, th)
00047 #define Spur_md_stop_line_LC(dev, x, y, th) YPSpur_md_stop_line(dev, CS_LC, x, y, th)
00048 #define Spur_md_stop_line_FS(dev, x, y, th) YPSpur_md_stop_line(dev, CS_FS, x, y, th)
00049 #define Spur_md_stop_line_BS(dev, x, y, th) YPSpur_md_stop_line(dev, CS_BS, x, y, th)
00050 #define Spur_md_stop_line_BL(dev, x, y, th) YPSpur_md_stop_line(dev, CS_BL, x, y, th)
00051 
00052 #define Spur_md_circle_GL(dev, x, y, d) YPSpur_md_circle(dev, CS_GL, x, y, d)
00053 #define Spur_md_circle_LC(dev, x, y, d) YPSpur_md_circle(dev, CS_LC, x, y, d)
00054 #define Spur_md_circle_FS(dev, x, y, d) YPSpur_md_circle(dev, CS_FS, x, y, d)
00055 #define Spur_md_circle_BS(dev, x, y, d) YPSpur_md_circle(dev, CS_BS, x, y, d)
00056 #define Spur_md_circle_BL(dev, x, y, d) YPSpur_md_circle(dev, CS_BL, x, y, d)
00057 
00058 #define Spur_md_spin_GL(dev, th) YPSpur_md_spin(dev, CS_GL, th)
00059 #define Spur_md_spin_LC(dev, th) YPSpur_md_spin(dev, CS_LC, th)
00060 #define Spur_md_spin_FS(dev, th) YPSpur_md_spin(dev, CS_FS, th)
00061 #define Spur_md_spin_BS(dev, th) YPSpur_md_spin(dev, CS_BS, th)
00062 #define Spur_md_spin_BL(dev, th) YPSpur_md_spin(dev, CS_BL, th)
00063 
00064 #define Spur_md_orient_GL(dev, th) YPSpur_md_orient(dev, CS_GL, th)
00065 #define Spur_md_orient_LC(dev, th) YPSpur_md_orient(dev, CS_LC, th)
00066 #define Spur_md_orient_FS(dev, th) YPSpur_md_orient(dev, CS_FS, th)
00067 #define Spur_md_orient_BS(dev, th) YPSpur_md_orient(dev, CS_BS, th)
00068 #define Spur_md_orient_BL(dev, th) YPSpur_md_orient(dev, CS_BL, th)
00069 
00070 #define Spur_md_set_pos_GL(dev, x, y, th) YPSpur_md_set_pos(dev, CS_GL, x, y, th)
00071 #define Spur_md_set_pos_LC(dev, x, y, th) YPSpur_md_set_pos(dev, CS_LC, x, y, th)
00072 #define Spur_md_set_pos_BL(dev, x, y, th) YPSpur_md_set_pos(dev, CS_BL, x, y, th)
00073 
00074 #define Spur_md_set_vel(dev, v) YPSpur_md_set_vel(dev, v)
00075 #define Spur_md_set_angvel(dev, w) YPSpur_md_set_angvel(dev, w)
00076 #define Spur_md_set_accel(dev, v) YPSpur_md_set_accel(dev, v)
00077 #define Spur_md_set_angaccel(dev, w) YPSpur_md_set_angaccel(dev, w)
00078 
00079 #define Spur_md_adjust_pos_GL(dev, x, y, th) YPSpur_md_adjust_pos(dev, CS_GL, x, y, th)
00080 #define Spur_md_adjust_pos_LC(dev, x, y, th) YPSpur_md_adjust_pos(dev, CS_LC, x, y, th)
00081 #define Spur_md_adjust_pos_FS(dev, x, y, th) YPSpur_md_adjust_pos(dev, CS_FS, x, y, th)
00082 #define Spur_md_adjust_pos_BS(dev, x, y, th) YPSpur_md_adjust_pos(dev, CS_BS, x, y, th)
00083 #define Spur_md_adjust_pos_BL(dev, x, y, th) YPSpur_md_adjust_pos(dev, CS_BL, x, y, th)
00084 
00085 #define Spur_md_get_pos_GL(dev, x, y, th) YPSpur_md_get_pos(dev, CS_GL, x, y, th)
00086 #define Spur_md_get_pos_LC(dev, x, y, th) YPSpur_md_get_pos(dev, CS_LC, x, y, th)
00087 #define Spur_md_get_pos_BS(dev, x, y, th) YPSpur_md_get_pos(dev, CS_BS, x, y, th)
00088 #define Spur_md_get_pos_BL(dev, x, y, th) YPSpur_md_get_pos(dev, CS_BL, x, y, th)
00089 
00090 #define Spur_md_get_vel(dev, v, w) YPSpur_md_get_vel(dev, v, w)
00091 #define Spur_md_get_force(dev, trans, angular) YPSpur_md_get_force(dev, trans, angular)
00092 
00093 #define Spur_md_near_pos_GL(dev, x, y, r) YPSpur_md_near_pos(dev, CS_GL, x, y, r)
00094 #define Spur_md_near_pos_LC(dev, x, y, r) YPSpur_md_near_pos(dev, CS_LC, x, y, r)
00095 #define Spur_md_near_pos_BS(dev, x, y, r) YPSpur_md_near_pos(dev, CS_BS, x, y, r)
00096 #define Spur_md_near_pos_BL(dev, x, y, r) YPSpur_md_near_pos(dev, CS_BL, x, y, r)
00097 
00098 #define Spur_md_near_ang_GL(dev, th, d) YPSpur_md_near_ang(dev, CS_GL, th, d)
00099 #define Spur_md_near_ang_LC(dev, th, d) YPSpur_md_near_ang(dev, CS_LC, th, d)
00100 #define Spur_md_near_ang_BS(dev, th, d) YPSpur_md_near_ang(dev, CS_BS, th, d)
00101 #define Spur_md_near_ang_BL(dev, th, d) YPSpur_md_near_ang(dev, CS_BL, th, d)
00102 
00103 #define Spur_md_over_line_GL(dev, x, y, th) YPSpur_md_over_line(dev, CS_GL, x, y, th)
00104 #define Spur_md_over_line_LC(dev, x, y, th) YPSpur_md_over_line(dev, CS_LC, x, y, th)
00105 #define Spur_md_over_line_BS(dev, x, y, th) YPSpur_md_over_line(dev, CS_BS, x, y, th)
00106 #define Spur_md_over_line_BL(dev, x, y, th) YPSpur_md_over_line(dev, CS_BL, x, y, th)
00107 
00108 #define Spur_md_vel(dev, v, w) YPSpur_md_vel(dev, v, w)
00109 
00110 #define Spur_md_tilt_GL(dev, d, t) YPSpur_md_tilt(dev, CS_GL, d, t)
00111 #define Spur_md_tilt_LC(dev, d, t) YPSpur_md_tilt(dev, CS_LC, d, t)
00112 #define Spur_md_tilt_FS(dev, d, t) YPSpur_md_tilt(dev, CS_FS, d, t)
00113 #define Spur_md_tilt_BS(dev, d, t) YPSpur_md_tilt(dev, CS_BS, d, t)
00114 #define Spur_md_tilt_BL(dev, d, t) YPSpur_md_tilt(dev, CS_BL, d, t)
00115 
00116 typedef struct
00117 {
00118   struct ipcmd_t dev;
00119   int pid;
00120   int connection_error;
00121 } YPSpur;
00122 
00124 int YPSpur_md_init(YPSpur *dev);
00125 int YPSpur_md_initex(YPSpur *dev, int msq_key);
00126 int YPSpur_md_init_socket(YPSpur *dev, char *ip, int port);
00127 
00129 int YPSpur_md_isfreeze(YPSpur *dev);
00130 int YPSpur_md_freeze(YPSpur *dev);
00131 int YPSpur_md_unfreeze(YPSpur *dev);
00132 
00134 int YPSpur_md_stop(YPSpur *dev);
00135 int YPSpur_md_free(YPSpur *dev);
00136 int YP_md_openfree(YPSpur *dev);
00137 
00139 int YPSpur_md_line(YPSpur *dev, int cs, double x, double y, double theta);
00140 int YPSpur_md_stop_line(YPSpur *dev, int cs, double x, double y, double theta);
00141 int YPSpur_md_circle(YPSpur *dev, int cs, double x, double y, double r);
00142 int YPSpur_md_spin(YPSpur *dev, int cs, double theta);
00143 int YPSpur_md_orient(YPSpur *dev, int cs, double theta);
00144 
00146 int YPSpur_md_set_pos(YPSpur *dev, int cs, double x, double y, double theta);
00147 int YPSpur_md_adjust_pos(YPSpur *dev, int cs, double x, double y, double theta);
00148 int YPSpur_md_set_vel(YPSpur *dev, double v);
00149 int YPSpur_md_set_angvel(YPSpur *dev, double w);
00150 int YPSpur_md_set_accel(YPSpur *dev, double v);
00151 int YPSpur_md_set_angaccel(YPSpur *dev, double w);
00152 
00154 double YPSpur_md_get_pos(YPSpur *dev, int cs, double *x, double *y, double *theta);
00155 double YPSpur_md_get_vel(YPSpur *dev, double *v, double *w);
00156 double YPSpur_md_get_force(YPSpur *dev, double *trans, double *angular);
00157 
00159 int YPSpur_md_near_pos(YPSpur *dev, int cs, double x, double y, double r);
00160 int YPSpur_md_near_ang(YPSpur *dev, int cs, double th, double d);
00161 int YPSpur_md_over_line(YPSpur *dev, int cs, double x, double y, double theta);
00162 
00164 int YPSpur_md_vel(YPSpur *dev, double v, double w);
00165 
00167 int YPSpur_md_tilt(YPSpur *dev, int cs, double dir, double tilt);
00168 
00169 /* 裏コマンド集 */
00170 int YP_md_get_error_state(YPSpur *dev);
00171 
00172 int YP_md_set_parameter(YPSpur *dev, int param_id, double value);
00173 int YP_md_set_parameter_array(YPSpur *dev, int param_id, double *value);
00174 int YP_md_get_parameter(YPSpur *dev, int param_id, double *value);
00175 int YP_md_get_parameter_array(YPSpur *dev, int param_id, double *value);
00176 int YP_md_set_control_state(YPSpur *dev, int control_id, int state);
00177 
00178 int YP_md_get_ad_value(YPSpur *dev, int num);
00179 int YP_md_set_io_dir(YPSpur *dev, unsigned char dir);
00180 int YP_md_set_io_data(YPSpur *dev, unsigned char data);
00181 double YP_md_get_device_error_state(YPSpur *dev, int id, int *err);
00182 int YP_md_wheel_vel(YPSpur *dev, double r, double l);
00183 int YP_md_wheel_torque(YPSpur *dev, double r, double l);
00184 double YP_md_get_wheel_vel(YPSpur *dev, double *wr, double *wl);
00185 double YP_md_get_wheel_ang(YPSpur *dev, double *theta_r, double *theta_l);
00186 double YP_md_get_wheel_torque(YPSpur *dev, double *torque_r, double *torque_l);
00187 int YP_md_set_wheel_vel(YPSpur *dev, double r, double l);
00188 int YP_md_set_wheel_accel(YPSpur *dev, double r, double l);
00189 int YP_md_wheel_ang(YPSpur *dev, double r, double l);
00190 double YP_md_get_vref(YPSpur *dev, double *vref, double *wref);
00191 double YP_md_get_wheel_vref(YPSpur *dev, double *wrref, double *wlref);
00192 
00193 int YP_md_joint_torque(YPSpur *spur, int id, double t);
00194 int YP_md_joint_vel(YPSpur *spur, int id, double v);
00195 int YP_md_joint_ang(YPSpur *spur, int id, double a);
00196 int YP_md_joint_ang_vel(YPSpur *spur, int id, double a, double v);
00197 int YP_md_set_joint_accel(YPSpur *spur, int id, double a);
00198 int YP_md_set_joint_vel(YPSpur *spur, int id, double v);
00199 double YP_md_get_joint_vel(YPSpur *spur, int id, double *v);
00200 double YP_md_get_joint_vref(YPSpur *spur, int id, double *v);
00201 double YP_md_get_joint_ang(YPSpur *spur, int id, double *a);
00202 double YP_md_get_joint_torque(YPSpur *spur, int id, double *t);
00203 
00204 #define YPSPUR_JOINT_SUPPORT 1
00205 #define YPSPUR_JOINT_ANG_VEL_SUPPORT 1
00206 #define YPSPUR_GET_DEVICE_ERROR_STATE_SUPPORT 1
00207 
00208 #ifdef __cplusplus
00209 }
00210 #endif  // __cplusplus
00211 #endif  // YPSPUR_MD_H


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