$search
00001 #include "comm_util_LL.h" 00002 00003 inline float degreesToRadians(float angle) 00004 { 00005 return angle * M_PI / 180.0; 00006 } 00007 00008 inline float radiansToDegrees(float angle) 00009 { 00010 return angle * 180.0 / M_PI; 00011 } 00012 00013 inline float LLToSIClimb(int16_t climb) 00014 { 00015 return ((float)(climb)) / 1000.0; 00016 } 00017 00018 // ****************** accel *********************** 00019 00020 float LLToSIAccX(int16_t acc, float g) 00021 { 00022 return ( - (float)(acc) ) / g * GRAVITY_SI ; 00023 } 00024 00025 float LLToSIAccY(int16_t acc, float g) 00026 { 00027 return ( - (float)(acc) ) / g * GRAVITY_SI ; 00028 } 00029 00030 float LLToSIAccZ(int16_t acc, float g) 00031 { 00032 return ( - (float)(acc) ) / g * GRAVITY_SI ; 00033 } 00034 00035 /* 00036 int32_t LLtoCommAccX(int16_t acc, float g) 00037 { 00038 return - (int32_t)((float)(acc) / g * GRAVITY_COMM); 00039 } 00040 00041 int32_t LLtoCommAccY(int16_t acc, float g) 00042 { 00043 return - (int32_t)((float)(acc) / g * GRAVITY_COMM); 00044 } 00045 00046 int32_t LLtoCommAccZ(int16_t acc, float g) 00047 { 00048 return - (int32_t)((float)(acc) / g * GRAVITY_COMM); 00049 } 00050 */ 00051 // ****************** angle *********************** 00052 00053 float LLToSIAngleRoll(int16_t angle) 00054 { 00055 float ta = degreesToRadians(((float)(-angle)) / 100.0); 00056 //normalizeSIAngle2Pi(&ta); 00057 return ta; 00058 } 00059 00060 float LLToSIAnglePitch(int16_t angle) 00061 { 00062 float ta = degreesToRadians(((float)(angle)) / 100.0); 00063 //normalizeSIAngle2Pi(&ta); 00064 return ta; 00065 } 00066 00067 float LLToSIAngleYaw(uint16_t angle) 00068 { 00069 float ta = degreesToRadians(((float)(36000-angle)) / 100.0); 00070 //normalizeSIAngle2Pi(&ta); 00071 return ta; 00072 } 00073 /* 00074 uint16_t LLtoCommAngleRoll(int16_t angle) 00075 { 00076 return (int)((-(float)(angle)) / 36000.0 * 65535.0); 00077 } 00078 00079 uint16_t LLtoCommAnglePitch(int16_t angle) 00080 { 00081 return (int)(((float)(angle)) / 36000.0 * 65535.0); 00082 } 00083 00084 uint16_t LLtoCommAngleYaw(uint16_t angle) 00085 { 00086 return (int)((36000.0 - (float)(angle)) / 36000.0 * 65535.0); 00087 } 00088 */ 00089 // ****************** angle rate *********************** 00090 00091 float LLToSIAngleRateYaw(int16_t angle_rate) 00092 { 00093 return degreesToRadians( (float)(-angle_rate) * 0.015 ); 00094 } 00095 00096 float LLToSIAngleRateRoll(int16_t angle_rate) 00097 { 00098 return degreesToRadians( (float)(-angle_rate) * 0.015 ); 00099 } 00100 00101 float LLToSIAngleRatePitch(int16_t angle_rate) 00102 { 00103 return degreesToRadians( (float)(angle_rate) * 0.015 ); 00104 } 00105 /* 00106 int32_t LLtoCommAngleRateYaw(int16_t angle_rate) 00107 { 00108 return (int32_t)((float)(-angle_rate) * 0.015 / 360.0 * 65535.0); 00109 } 00110 */ 00111 // ******* motor commands *** 00112 00113 short SIToLLCmdRoll (float angle_cmd) 00114 { 00115 return -((short)(angle_cmd * 2293.578 )); // minus to invert roll because of the frame conversion (ASCTEC coordinate frame(??) to ENU) 00116 } 00117 00118 short SIToLLCmdPitch (float angle_cmd) 00119 { 00120 return ((short)(angle_cmd * 2293.578 )); 00121 } 00122 00123 short SIToLLCmdYawRate (float yaw_rate_cmd) 00124 { 00125 return ((short)(yaw_rate_cmd * 460.37235)); // minus to invert yaw rate because of the frame conversion (ASCTEC coordinate frame(??) to ENU) 00126 } 00127 00128 short SIToLLCmdThrust (float thrust_cmd) 00129 { 00130 return (short)(thrust_cmd * 40.95 ); 00131 } 00132 /* 00133 short commToLLCmdRoll (int16_t cmd_roll) 00134 { 00135 return -(short) ( ((float)(cmd_roll)) / 65535 * (2.0 * M_PI) * 2293.578); 00136 //return -((short)((float) cmd_roll / 1000.0 * 2293.578 )); 00137 } 00138 short commToLLCmdPitch (int16_t cmd_pitch) 00139 { 00140 return (short) ( ((float)(cmd_pitch)) / 65535 * (2.0 * M_PI) * 2293.578); 00141 //return ((short)((float) cmd_pitch/ 1000.0 * 2293.578 )); 00142 } 00143 short commToLLCmdYawRate (int32_t cmd_yaw_rate) 00144 { 00145 return -((short)((float)(cmd_yaw_rate)) / 65535 * (2.0 * M_PI) * 460.37235); 00146 //return -((short)((float) cmd_yaw_rate / 1000.0 * 460.37235)); 00147 } 00148 00149 short commToLLCmdThrust (int16_t cmd_thrust) 00150 { 00151 return (short)((float)(cmd_thrust) / 10000.0 * 4095 ); 00152 } 00153 */