|
|
@ -60,7 +60,7 @@ void Copter::zr_app_10hz() |
|
|
|
if(zr_serial_api.data_trans_init){ |
|
|
|
if(zr_serial_api.data_trans_init){ |
|
|
|
// void AC_ZR_Serial_API::get_vehicle_status(uint8_t mode,uint8_t in_air,uint32_t home_distance,uint16_t volt_mv,uint8_t bat_remaining)
|
|
|
|
// void AC_ZR_Serial_API::get_vehicle_status(uint8_t mode,uint8_t in_air,uint32_t home_distance,uint16_t volt_mv,uint8_t bat_remaining)
|
|
|
|
uint16_t now_volt = uint16_t(battery.voltage() * 100); |
|
|
|
uint16_t now_volt = uint16_t(battery.voltage() * 100); |
|
|
|
zr_serial_api.get_vehicle_status((uint8_t)control_mode,(uint8_t)flightmode->is_landing(),home_distance(),now_volt,battery.capacity_remaining_pct()); |
|
|
|
zr_serial_api.get_vehicle_status((uint8_t)control_mode,!ap.land_complete,home_distance(),now_volt,battery.capacity_remaining_pct()); |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
@ -96,7 +96,7 @@ void Copter::zr_app_50hz(){ |
|
|
|
if(ahrs.get_secondary_attitude(euler)){ |
|
|
|
if(ahrs.get_secondary_attitude(euler)){ |
|
|
|
euler_deg.x = degrees(euler.x); |
|
|
|
euler_deg.x = degrees(euler.x); |
|
|
|
euler_deg.y = degrees(euler.y); |
|
|
|
euler_deg.y = degrees(euler.y); |
|
|
|
euler_deg.z = wrap_360_cd(degrees(euler.z)); |
|
|
|
euler_deg.z = wrap_360(degrees(euler.z)); |
|
|
|
// zr_serial_api.get_vehicle_euler_angles(euler_deg);
|
|
|
|
// zr_serial_api.get_vehicle_euler_angles(euler_deg);
|
|
|
|
// gcs().send_text(MAV_SEVERITY_INFO,"get euler:%.2f,%.2f,%.2f",euler_deg.x,euler_deg.y,euler_deg.z);
|
|
|
|
// gcs().send_text(MAV_SEVERITY_INFO,"get euler:%.2f,%.2f,%.2f",euler_deg.x,euler_deg.y,euler_deg.z);
|
|
|
|
} |
|
|
|
} |
|
|
@ -117,9 +117,15 @@ void Copter::zr_app_50hz(){ |
|
|
|
float yaw_deg; |
|
|
|
float yaw_deg; |
|
|
|
bool new_data = zr_serial_api.get_control_data((uint8_t)control_mode ,msg_type,data,yaw_deg); |
|
|
|
bool new_data = zr_serial_api.get_control_data((uint8_t)control_mode ,msg_type,data,yaw_deg); |
|
|
|
if(new_data){ |
|
|
|
if(new_data){ |
|
|
|
|
|
|
|
static char buf[50]; |
|
|
|
int32_t ahrs_yaw_cd = wrap_360_cd(int32_t(yaw_deg * 100)); |
|
|
|
int32_t ahrs_yaw_cd = wrap_360_cd(int32_t(yaw_deg * 100)); |
|
|
|
gcs().send_text(MAV_SEVERITY_INFO,"get msg_type:%d, data:%ld,%ld,%ld, y:%.2f",(int)msg_type,data.x,data.y,data.z,yaw_deg); |
|
|
|
// gcs().send_text(MAV_SEVERITY_INFO,"get msg_type:%d, data:%ld,%ld,%ld, y:%.2f",(int)msg_type,data.x,data.y,data.z,yaw_deg);
|
|
|
|
|
|
|
|
// zr_serial_api.print_data("get msg_type:%d, data:%ld,%ld,%ld, y:%.2f",(int)msg_type,data.x,data.y,data.z,yaw_deg);
|
|
|
|
|
|
|
|
if(zr_serial_api.get_param_debug()){ |
|
|
|
|
|
|
|
snprintf(buf, sizeof(buf), "type:%d, data:%ld,%ld,%ld, y:%.2f",(int)msg_type,data.x,data.y,data.z,yaw_deg); |
|
|
|
|
|
|
|
zr_serial_api.print_msg(buf); |
|
|
|
|
|
|
|
memset(buf,0,50); |
|
|
|
|
|
|
|
} |
|
|
|
switch (msg_type) |
|
|
|
switch (msg_type) |
|
|
|
{ |
|
|
|
{ |
|
|
|
case AC_ZR_Serial_API::ZR_Msg_Type::MSG_CONTROL_TKOFF: |
|
|
|
case AC_ZR_Serial_API::ZR_Msg_Type::MSG_CONTROL_TKOFF: |
|
|
@ -132,7 +138,13 @@ void Copter::zr_app_50hz(){ |
|
|
|
} |
|
|
|
} |
|
|
|
float tk_alt = (data.z)/100.0; |
|
|
|
float tk_alt = (data.z)/100.0; |
|
|
|
start_takeoff(tk_alt); |
|
|
|
start_takeoff(tk_alt); |
|
|
|
gcs().send_text(MAV_SEVERITY_INFO,"do takeoff,alt %.2f",tk_alt); |
|
|
|
if(zr_serial_api.get_param_debug()){ |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// zr_serial_api.print_data("do takeoff,alt %.2f",tk_alt);
|
|
|
|
|
|
|
|
snprintf(buf, sizeof(buf), "do takeoff,alt %.2f",tk_alt); |
|
|
|
|
|
|
|
zr_serial_api.print_msg(buf); |
|
|
|
|
|
|
|
memset(buf,0,50); |
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
break; |
|
|
|
break; |
|
|
|
case AC_ZR_Serial_API::ZR_Msg_Type::MSG_CONTROL_POS: |
|
|
|
case AC_ZR_Serial_API::ZR_Msg_Type::MSG_CONTROL_POS: |
|
|
@ -143,7 +155,12 @@ void Copter::zr_app_50hz(){ |
|
|
|
target_loc.alt = (data.z + 500); |
|
|
|
target_loc.alt = (data.z + 500); |
|
|
|
// target_loc.alt = (data.z + 500)/100.0;
|
|
|
|
// target_loc.alt = (data.z + 500)/100.0;
|
|
|
|
set_target_location(target_loc,ahrs_yaw_cd); |
|
|
|
set_target_location(target_loc,ahrs_yaw_cd); |
|
|
|
gcs().send_text(MAV_SEVERITY_INFO,"set location,lat %ld,%ld,%ld",target_loc.lat,target_loc.lng,target_loc.alt); |
|
|
|
if(zr_serial_api.get_param_debug()){ |
|
|
|
|
|
|
|
// zr_serial_api.print_data("set location,lat %ld,%ld,%ld",target_loc.lat,target_loc.lng,target_loc.alt);
|
|
|
|
|
|
|
|
snprintf(buf, sizeof(buf), "set location,lat %ld,%ld,%ld",target_loc.lat,target_loc.lng,target_loc.alt); |
|
|
|
|
|
|
|
zr_serial_api.print_msg(buf); |
|
|
|
|
|
|
|
memset(buf,0,50); |
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
break; |
|
|
|
break; |
|
|
|
case AC_ZR_Serial_API::ZR_Msg_Type::MSG_CONTROL_VEL: |
|
|
|
case AC_ZR_Serial_API::ZR_Msg_Type::MSG_CONTROL_VEL: |
|
|
@ -155,8 +172,13 @@ void Copter::zr_app_50hz(){ |
|
|
|
// target_loc.alt = (data.z + 500)/100.0;
|
|
|
|
// target_loc.alt = (data.z + 500)/100.0;
|
|
|
|
// set_target_velocity_NED(target_vel);
|
|
|
|
// set_target_velocity_NED(target_vel);
|
|
|
|
mode_guided.set_velocity(target_vel,true,ahrs_yaw_cd,false,0.0f,false,true); |
|
|
|
mode_guided.set_velocity(target_vel,true,ahrs_yaw_cd,false,0.0f,false,true); |
|
|
|
|
|
|
|
if(zr_serial_api.get_param_debug()){ |
|
|
|
|
|
|
|
|
|
|
|
gcs().send_text(MAV_SEVERITY_INFO,"set vel %.2f,%.2f,%.2f",target_vel.x,target_vel.y,target_vel.z); |
|
|
|
// zr_serial_api.print_data("set vel %.2f,%.2f,%.2f",target_vel.x,target_vel.y,target_vel.z);
|
|
|
|
|
|
|
|
snprintf(buf, sizeof(buf), "set vel %.2f,%.2f,%.2f",target_vel.x,target_vel.y,target_vel.z); |
|
|
|
|
|
|
|
zr_serial_api.print_msg(buf); |
|
|
|
|
|
|
|
memset(buf,0,50); |
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
break; |
|
|
|
break; |
|
|
|
case AC_ZR_Serial_API::ZR_Msg_Type::MSG_CONTROL_VEL_P: |
|
|
|
case AC_ZR_Serial_API::ZR_Msg_Type::MSG_CONTROL_VEL_P: |
|
|
@ -182,10 +204,60 @@ void Copter::zr_app_50hz(){ |
|
|
|
// convert vector to neu in cm
|
|
|
|
// convert vector to neu in cm
|
|
|
|
const Vector3f vel_neu_cms(ne_x, ne_y, -target_vel.z); |
|
|
|
const Vector3f vel_neu_cms(ne_x, ne_y, -target_vel.z); |
|
|
|
mode_guided.set_velocity(vel_neu_cms,true,ahrs_yaw_cd,false,0.0f,false,true); |
|
|
|
mode_guided.set_velocity(vel_neu_cms,true,ahrs_yaw_cd,false,0.0f,false,true); |
|
|
|
|
|
|
|
if(zr_serial_api.get_param_debug()){ |
|
|
|
|
|
|
|
// zr_serial_api.print_data("set speed %.2f,%.2f,%.2f,yaw:%ld",ne_x,ne_y,target_vel.z,ahrs_yaw_cd);
|
|
|
|
|
|
|
|
snprintf(buf, sizeof(buf), "set speed %.2f,%.2f,%.2f,yaw:%ld",ne_x,ne_y,target_vel.z,ahrs_yaw_cd); |
|
|
|
|
|
|
|
zr_serial_api.print_msg(buf); |
|
|
|
|
|
|
|
memset(buf,0,50); |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
break; |
|
|
|
|
|
|
|
case AC_ZR_Serial_API::ZR_Msg_Type::MSG_CONTROL_VEL_LOCK_YAW: |
|
|
|
|
|
|
|
if(motors->armed()){ |
|
|
|
|
|
|
|
Vector3f target_vel; |
|
|
|
|
|
|
|
target_vel.x = 0; |
|
|
|
|
|
|
|
target_vel.y = 0; |
|
|
|
|
|
|
|
target_vel.z = 0; |
|
|
|
|
|
|
|
// target_loc.alt = (data.z + 500)/100.0;
|
|
|
|
|
|
|
|
// set_target_velocity_NED(target_vel);
|
|
|
|
|
|
|
|
mode_guided.set_velocity(target_vel,false,ahrs_yaw_cd,false,0.0f,false,true); |
|
|
|
|
|
|
|
if(zr_serial_api.get_param_debug()){ |
|
|
|
|
|
|
|
|
|
|
|
gcs().send_text(MAV_SEVERITY_INFO,"set speed %.2f,%.2f,%.2f,yaw:%ld",ne_x,ne_y,target_vel.z,ahrs_yaw_cd); |
|
|
|
// zr_serial_api.print_data("set vel %.2f,%.2f,%.2f",target_vel.x,target_vel.y,target_vel.z);
|
|
|
|
|
|
|
|
snprintf(buf, sizeof(buf), "set vel %.2f,%.2f,%.2f,lock yaw",target_vel.x,target_vel.y,target_vel.z); |
|
|
|
|
|
|
|
zr_serial_api.print_msg(buf); |
|
|
|
|
|
|
|
memset(buf,0,50); |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
break; |
|
|
|
|
|
|
|
case AC_ZR_Serial_API::ZR_Msg_Type::MSG_CONTROL_MODE: |
|
|
|
|
|
|
|
{ |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
if(control_mode != Mode::Number::GUIDED){ |
|
|
|
|
|
|
|
set_mode(Mode::Number::GUIDED, ModeReason::SCRIPTING); |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
uint8_t user_mode = (data.x); |
|
|
|
|
|
|
|
if(user_mode == 3 || user_mode == 4 || user_mode == 6 || user_mode == 17){ |
|
|
|
|
|
|
|
bool change_ok = set_mode(user_mode, ModeReason::SCRIPTING); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
if(zr_serial_api.get_param_debug() && change_ok){ |
|
|
|
|
|
|
|
// zr_serial_api.print_data("do takeoff,alt %.2f",tk_alt);
|
|
|
|
|
|
|
|
snprintf(buf, sizeof(buf), "Change mode %d",user_mode); |
|
|
|
|
|
|
|
zr_serial_api.print_msg(buf); |
|
|
|
|
|
|
|
memset(buf,0,50); |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
}else{ |
|
|
|
|
|
|
|
if(zr_serial_api.get_param_debug()){ |
|
|
|
|
|
|
|
// zr_serial_api.print_data("do takeoff,alt %.2f",tk_alt);
|
|
|
|
|
|
|
|
snprintf(buf, sizeof(buf), "Unsupported mode %d",user_mode); |
|
|
|
|
|
|
|
zr_serial_api.print_msg(buf); |
|
|
|
|
|
|
|
memset(buf,0,50); |
|
|
|
|
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
} |
|
|
|
break; |
|
|
|
break; |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
default: |
|
|
|
default: |
|
|
|
break; |
|
|
|
break; |
|
|
|