public IHttpActionResult setMode(string id, [FromBody] SetModeAction parameters) { String action = "setMode"; logger.Debug("running command {1} on /drones/{0}", id, action); if (null == parameters) { return(BadRequest("Missing Required Parameters")); } Drone target = droneMgr.getById(new Guid(id)); if (null != target) { if (!target.isConnected()) { return(BadRequest("Target system is not connected, refusing request")); } MAVLink.MAV_MODE mode = 0; try { mode = (MAVLink.MAV_MODE)Enum.Parse(typeof(MAVLink.MAV_MODE), parameters.mode); } catch (Exception e) { return(BadRequest(e.Message)); } CommandAck result = target.Command.setMode(mode); if (null == result) { return(new CustomResponse("Null command result.", HttpStatusCode.RequestTimeout)); } return(Ok(DTOFactory.DTOFactory.createCommandAckDTO(result))); } else { return(NotFound()); } }
/* * 176 MAV_CMD_DO_SET_MODE Set system mode. * Mission Param #1 Mode, as defined by ENUM MAV_MODE * Mission Param #2 Custom mode - this is system specific, please refer to the individual autopilot specifications for details. * Mission Param #3 Custom sub mode - this is system specific, please refer to the individual autopilot specifications for details. * Mission Param #4 Empty * Mission Param #5 Empty * Mission Param #6 Empty * Mission Param #7 Empty */ public CommandAck setMode(MAVLink.MAV_MODE mode) { return(runCommand(MAVLink.MAV_CMD.DO_SET_MODE, (int)mode, default(Int32), default(Int32), default(Int32), default(Int32), default(Int32), default(Int32))); }