Commit 52c34e85 authored by lm's avatar lm

Updated to v1.0

parent 946acc18
...@@ -546,14 +546,14 @@ void MAVLinkSimulationLink::mainloop() ...@@ -546,14 +546,14 @@ void MAVLinkSimulationLink::mainloop()
static int typeCounter = 0; static int typeCounter = 0;
uint8_t mavType; uint8_t mavType;
if (typeCounter < 10) { if (typeCounter < 10) {
mavType = MAV_QUADROTOR; mavType = MAV_TYPE_QUADROTOR;
} else { } else {
mavType = typeCounter % (OCU); mavType = typeCounter % (MAV_TYPE_OCU);
} }
typeCounter++; typeCounter++;
// Pack message and get size of encoded byte string // Pack message and get size of encoded byte string
messageSize = mavlink_msg_heartbeat_pack(systemId, componentId, &msg, mavType, MAV_AUTOPILOT_PIXHAWK); messageSize = mavlink_msg_heartbeat_pack(systemId, componentId, &msg, mavType, MAV_CLASS_PIXHAWK);
// Allocate buffer with packet data // Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg); bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream //add data into datastream
...@@ -722,31 +722,32 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size) ...@@ -722,31 +722,32 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
qDebug() << "SIM" << "received action" << action.action << "for system" << action.target; qDebug() << "SIM" << "received action" << action.action << "for system" << action.target;
switch (action.action) { // FIXME MAVLINKV10PORTINGNEEDED
case MAV_ACTION_LAUNCH: // switch (action.action) {
status.status = MAV_STATE_ACTIVE; // case MAV_ACTION_LAUNCH:
status.mode = MAV_MODE_AUTO; // status.status = MAV_STATE_ACTIVE;
break; // status.mode = MAV_MODE_AUTO;
case MAV_ACTION_RETURN: // break;
status.status = MAV_STATE_ACTIVE; // case MAV_ACTION_RETURN:
break; // status.status = MAV_STATE_ACTIVE;
case MAV_ACTION_MOTORS_START: // break;
status.status = MAV_STATE_ACTIVE; // case MAV_ACTION_MOTORS_START:
status.mode = MAV_MODE_LOCKED; // status.status = MAV_STATE_ACTIVE;
break; // status.mode = MAV_MODE_LOCKED;
case MAV_ACTION_MOTORS_STOP: // break;
status.status = MAV_STATE_STANDBY; // case MAV_ACTION_MOTORS_STOP:
status.mode = MAV_MODE_LOCKED; // status.status = MAV_STATE_STANDBY;
break; // status.mode = MAV_MODE_LOCKED;
case MAV_ACTION_EMCY_KILL: // break;
status.status = MAV_STATE_EMERGENCY; // case MAV_ACTION_EMCY_KILL:
status.mode = MAV_MODE_MANUAL; // status.status = MAV_STATE_EMERGENCY;
break; // status.mode = MAV_MODE_MANUAL;
case MAV_ACTION_SHUTDOWN: // break;
status.status = MAV_STATE_POWEROFF; // case MAV_ACTION_SHUTDOWN:
status.mode = MAV_MODE_LOCKED; // status.status = MAV_STATE_POWEROFF;
break; // status.mode = MAV_MODE_LOCKED;
} // break;
// }
} }
break; break;
#ifdef MAVLINK_ENABLED_PIXHAWK #ifdef MAVLINK_ENABLED_PIXHAWK
...@@ -771,7 +772,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size) ...@@ -771,7 +772,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
for (i = onboardParams.begin(); i != onboardParams.end(); ++i) { for (i = onboardParams.begin(); i != onboardParams.end(); ++i) {
if (j != 5) { if (j != 5) {
// Pack message and get size of encoded byte string // Pack message and get size of encoded byte string
mavlink_msg_param_value_pack(read.target_system, componentId, &msg, (int8_t*)i.key().toStdString().c_str(), i.value(), onboardParams.size(), j); mavlink_msg_param_value_pack(read.target_system, componentId, &msg, i.key().toStdString().c_str(), i.value(), onboardParams.size(), j);
// Allocate buffer with packet data // Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg); bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream //add data into datastream
...@@ -799,7 +800,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size) ...@@ -799,7 +800,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
onboardParams.insert(key, set.param_value); onboardParams.insert(key, set.param_value);
// Pack message and get size of encoded byte string // Pack message and get size of encoded byte string
mavlink_msg_param_value_pack(set.target_system, componentId, &msg, (int8_t*)key.toStdString().c_str(), set.param_value, onboardParams.size(), onboardParams.keys().indexOf(key)); mavlink_msg_param_value_pack(set.target_system, componentId, &msg, key.toStdString().c_str(), set.param_value, onboardParams.size(), onboardParams.keys().indexOf(key));
// Allocate buffer with packet data // Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg); bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream //add data into datastream
...@@ -820,7 +821,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size) ...@@ -820,7 +821,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
float paramValue = onboardParams.value(key); float paramValue = onboardParams.value(key);
// Pack message and get size of encoded byte string // Pack message and get size of encoded byte string
mavlink_msg_param_value_pack(read.target_system, componentId, &msg, (int8_t*)key.toStdString().c_str(), paramValue, onboardParams.size(), onboardParams.keys().indexOf(key)); mavlink_msg_param_value_pack(read.target_system, componentId, &msg, key.toStdString().c_str(), paramValue, onboardParams.size(), onboardParams.keys().indexOf(key));
// Allocate buffer with packet data // Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg); bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream //add data into datastream
...@@ -832,7 +833,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size) ...@@ -832,7 +833,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
float paramValue = onboardParams.value(key); float paramValue = onboardParams.value(key);
// Pack message and get size of encoded byte string // Pack message and get size of encoded byte string
mavlink_msg_param_value_pack(read.target_system, componentId, &msg, (int8_t*)key.toStdString().c_str(), paramValue, onboardParams.size(), onboardParams.keys().indexOf(key)); mavlink_msg_param_value_pack(read.target_system, componentId, &msg, key.toStdString().c_str(), paramValue, onboardParams.size(), onboardParams.keys().indexOf(key));
// Allocate buffer with packet data // Allocate buffer with packet data
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg); bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
//add data into datastream //add data into datastream
......
...@@ -68,7 +68,7 @@ void MAVLinkSimulationMAV::mainloop() ...@@ -68,7 +68,7 @@ void MAVLinkSimulationMAV::mainloop()
// 1 Hz execution // 1 Hz execution
if (timer1Hz <= 0) { if (timer1Hz <= 0) {
mavlink_message_t msg; mavlink_message_t msg;
mavlink_msg_heartbeat_pack_version_free(systemid, MAV_COMP_ID_IMU, &msg, MAV_FIXED_WING, MAV_AUTOPILOT_PIXHAWK, mavlink_version); mavlink_msg_heartbeat_pack(systemid, MAV_COMP_ID_IMU, &msg, MAV_TYPE_FIXED_WING, MAV_CLASS_PIXHAWK);
link->sendMAVLinkMessage(&msg); link->sendMAVLinkMessage(&msg);
planner.handleMessage(msg); planner.handleMessage(msg);
...@@ -306,30 +306,31 @@ void MAVLinkSimulationMAV::handleMessage(const mavlink_message_t& msg) ...@@ -306,30 +306,31 @@ void MAVLinkSimulationMAV::handleMessage(const mavlink_message_t& msg)
if (systemid == mode.target) sys_mode = mode.mode; if (systemid == mode.target) sys_mode = mode.mode;
} }
break; break;
case MAVLINK_MSG_ID_ACTION: { // FIXME MAVLINKV10PORTINGNEEDED
mavlink_action_t action; // case MAVLINK_MSG_ID_ACTION: {
mavlink_msg_action_decode(&msg, &action); // mavlink_action_t action;
if (systemid == action.target && (action.target_component == 0 || action.target_component == MAV_COMP_ID_IMU)) { // mavlink_msg_action_decode(&msg, &action);
mavlink_action_ack_t ack; // if (systemid == action.target && (action.target_component == 0 || action.target_component == MAV_COMP_ID_IMU)) {
ack.action = action.action; // mavlink_action_ack_t ack;
switch (action.action) { // ack.action = action.action;
case MAV_ACTION_TAKEOFF: //// switch (action.action) {
flying = true; //// case MAV_ACTION_TAKEOFF:
nav_mode = MAV_NAV_LIFTOFF; //// flying = true;
ack.result = 1; //// nav_mode = MAV_NAV_LIFTOFF;
break; //// ack.result = 1;
default: { //// break;
ack.result = 0; //// default: {
} //// ack.result = 0;
break; //// }
} //// break;
//// }
// Give feedback about action
mavlink_message_t r_msg; // // Give feedback about action
mavlink_msg_action_ack_encode(systemid, MAV_COMP_ID_IMU, &r_msg, &ack); // mavlink_message_t r_msg;
link->sendMAVLinkMessage(&r_msg); // mavlink_msg_action_ack_encode(systemid, MAV_COMP_ID_IMU, &r_msg, &ack);
} // link->sendMAVLinkMessage(&r_msg);
} // }
// }
break; break;
case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET: { case MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET: {
mavlink_local_position_setpoint_set_t sp; mavlink_local_position_setpoint_set_t sp;
......
...@@ -55,16 +55,17 @@ protected: ...@@ -55,16 +55,17 @@ protected:
bool flying; bool flying;
int mavlink_version; int mavlink_version;
static inline uint16_t mavlink_msg_heartbeat_pack_version_free(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t type, uint8_t autopilot, uint8_t version) { // FIXME MAVLINKV10PORTINGNEEDED
uint16_t i = 0; // static inline uint16_t mavlink_msg_heartbeat_pack_version_free(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t type, uint8_t autopilot, uint8_t version) {
msg->msgid = MAVLINK_MSG_ID_HEARTBEAT; // uint16_t i = 0;
// msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
i += put_uint8_t_by_index(type, i, msg->payload); // Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) // i += put_uint8_t_by_index(type, i, msg->payload); // Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
i += put_uint8_t_by_index(autopilot, i, msg->payload); // Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM // i += put_uint8_t_by_index(autopilot, i, msg->payload); // Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
i += put_uint8_t_by_index(version, i, msg->payload); // MAVLink version // i += put_uint8_t_by_index(version, i, msg->payload); // MAVLink version
return mavlink_finalize_message(msg, system_id, component_id, i); // return mavlink_finalize_message(msg, system_id, component_id, i);
} // }
}; };
......
...@@ -10,16 +10,21 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte ...@@ -10,16 +10,21 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
{ {
QPointer<QObject> p; QPointer<QObject> p;
if (parent != NULL) { if (parent != NULL)
{
p = parent; p = parent;
} else { }
else
{
p = mavlink; p = mavlink;
} }
UASInterface* uas; UASInterface* uas;
switch (heartbeat->autopilot) { switch (heartbeat->autopilot)
case MAV_AUTOPILOT_GENERIC: { {
case MAV_CLASS_GENERIC:
{
UAS* mav = new UAS(mavlink, sysid); UAS* mav = new UAS(mavlink, sysid);
// Set the system type // Set the system type
mav->setSystemType((int)heartbeat->type); mav->setSystemType((int)heartbeat->type);
...@@ -28,7 +33,8 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte ...@@ -28,7 +33,8 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
uas = mav; uas = mav;
} }
break; break;
case MAV_AUTOPILOT_PIXHAWK: { case MAV_CLASS_PIXHAWK:
{
PxQuadMAV* mav = new PxQuadMAV(mavlink, sysid); PxQuadMAV* mav = new PxQuadMAV(mavlink, sysid);
// Set the system type // Set the system type
mav->setSystemType((int)heartbeat->type); mav->setSystemType((int)heartbeat->type);
...@@ -40,7 +46,8 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte ...@@ -40,7 +46,8 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
uas = mav; uas = mav;
} }
break; break;
case MAV_AUTOPILOT_SLUGS: { case MAV_CLASS_SLUGS:
{
SlugsMAV* mav = new SlugsMAV(mavlink, sysid); SlugsMAV* mav = new SlugsMAV(mavlink, sysid);
// Set the system type // Set the system type
mav->setSystemType((int)heartbeat->type); mav->setSystemType((int)heartbeat->type);
...@@ -52,7 +59,8 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte ...@@ -52,7 +59,8 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
uas = mav; uas = mav;
} }
break; break;
case MAV_AUTOPILOT_ARDUPILOTMEGA: { case MAV_CLASS_ARDUPILOTMEGA:
{
ArduPilotMegaMAV* mav = new ArduPilotMegaMAV(mavlink, sysid); ArduPilotMegaMAV* mav = new ArduPilotMegaMAV(mavlink, sysid);
// Set the system type // Set the system type
mav->setSystemType((int)heartbeat->type); mav->setSystemType((int)heartbeat->type);
...@@ -64,7 +72,8 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte ...@@ -64,7 +72,8 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
uas = mav; uas = mav;
} }
break; break;
default: { default:
{
UAS* mav = new UAS(mavlink, sysid); UAS* mav = new UAS(mavlink, sysid);
mav->setSystemType((int)heartbeat->type); mav->setSystemType((int)heartbeat->type);
// Connect this robot to the UAS object // Connect this robot to the UAS object
......
This diff is collapsed.
...@@ -253,8 +253,6 @@ public slots: ...@@ -253,8 +253,6 @@ public slots:
} }
/** @brief Set a new name **/ /** @brief Set a new name **/
void setUASName(const QString& name); void setUASName(const QString& name);
/** @brief Executes an action **/
void setAction(MAV_ACTION action);
/** @brief Executes a command **/ /** @brief Executes a command **/
void executeCommand(MAV_CMD command); void executeCommand(MAV_CMD command);
/** @brief Executes a command **/ /** @brief Executes a command **/
......
...@@ -188,8 +188,6 @@ public slots: ...@@ -188,8 +188,6 @@ public slots:
/** @brief Set a new name for the system */ /** @brief Set a new name for the system */
virtual void setUASName(const QString& name) = 0; virtual void setUASName(const QString& name) = 0;
/** @brief Sets an action **/
virtual void setAction(MAV_ACTION action) = 0;
/** @brief Execute command immediately **/ /** @brief Execute command immediately **/
virtual void executeCommand(MAV_CMD command) = 0; virtual void executeCommand(MAV_CMD command) = 0;
/** @brief Executes a command **/ /** @brief Executes a command **/
......
...@@ -586,8 +586,10 @@ int UASWaypointManager::getLocalFrameCount() ...@@ -586,8 +586,10 @@ int UASWaypointManager::getLocalFrameCount()
// Search through all waypoints, // Search through all waypoints,
// counting only those in global frame // counting only those in global frame
int i = 0; int i = 0;
foreach (Waypoint* p, waypoints) { foreach (Waypoint* p, waypoints)
if (p->getFrame() == MAV_FRAME_GLOBAL) { {
if (p->getFrame() == MAV_FRAME_GLOBAL)
{
i++; i++;
} }
} }
...@@ -600,8 +602,10 @@ int UASWaypointManager::getLocalFrameIndexOf(Waypoint* wp) ...@@ -600,8 +602,10 @@ int UASWaypointManager::getLocalFrameIndexOf(Waypoint* wp)
// Search through all waypoints, // Search through all waypoints,
// counting only those in local frame // counting only those in local frame
int i = 0; int i = 0;
foreach (Waypoint* p, waypoints) { foreach (Waypoint* p, waypoints)
if (p->getFrame() == MAV_FRAME_LOCAL) { {
if (p->getFrame() == MAV_FRAME_LOCAL_NED || p->getFrame() == MAV_FRAME_LOCAL_ENU)
{
if (p == wp) { if (p == wp) {
return i; return i;
} }
...@@ -617,7 +621,8 @@ int UASWaypointManager::getMissionFrameIndexOf(Waypoint* wp) ...@@ -617,7 +621,8 @@ int UASWaypointManager::getMissionFrameIndexOf(Waypoint* wp)
// Search through all waypoints, // Search through all waypoints,
// counting only those in mission frame // counting only those in mission frame
int i = 0; int i = 0;
foreach (Waypoint* p, waypoints) { foreach (Waypoint* p, waypoints)
{
if (p->getFrame() == MAV_FRAME_MISSION) { if (p->getFrame() == MAV_FRAME_MISSION) {
if (p == wp) { if (p == wp) {
return i; return i;
......
...@@ -355,7 +355,7 @@ void DebugConsole::receiveBytes(LinkInterface* link, QByteArray bytes) ...@@ -355,7 +355,7 @@ void DebugConsole::receiveBytes(LinkInterface* link, QByteArray bytes)
for (int j = 0; j < len; j++) for (int j = 0; j < len; j++)
{ {
unsigned char byte = bytes.at(j); unsigned char byte = bytes.at(j);
// Filter MAVLink (http://pixhawk.ethz.ch/wiki/mavlink/) messages out of the stream. // Filter MAVLink (http://qgroundcontrol.org/mavlink/) messages out of the stream.
if (filterMAVLINK) if (filterMAVLINK)
{ {
if (this->bytesToIgnore > 0) if (this->bytesToIgnore > 0)
......
This diff is collapsed.
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment