Browse Source

Replaced home command with land command.

QGC4.4
pixhawk 13 years ago
parent
commit
0075f51261
  1. 15
      src/uas/UAS.cc
  2. 4
      src/uas/UAS.h
  3. 2
      src/uas/UASInterface.h
  4. 2
      src/ui/uas/UASView.cc

15
src/uas/UAS.cc

@ -249,9 +249,9 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
switch (message.compid) switch (message.compid)
{ {
case MAV_COMP_ID_IMU_2: case MAV_COMP_ID_IMU:
// Prefer IMU 2 over IMU 1 (FIXME) // Prefer IMU 2 over IMU 1 (FIXME)
componentID[message.msgid] = MAV_COMP_ID_IMU_2; componentID[message.msgid] = MAV_COMP_ID_IMU;
break; break;
default: default:
// Do nothing // Do nothing
@ -2236,7 +2236,7 @@ void UAS::go()
sendMessage(msg); sendMessage(msg);
} }
/** Order the robot to return home / to land on the runway **/ /** Order the robot to return home **/
void UAS::home() void UAS::home()
{ {
mavlink_message_t msg; mavlink_message_t msg;
@ -2250,6 +2250,15 @@ void UAS::home()
sendMessage(msg); sendMessage(msg);
} }
/** Order the robot to land on the runway **/
void UAS::land()
{
mavlink_message_t msg;
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_NAV_LAND, 1, 0, 0, 0, 0, 0, 0, 0);
sendMessage(msg);
}
/** /**
* The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation * The MAV starts the emergency landing procedure. The behaviour depends on the onboard implementation
* and might differ between systems. * and might differ between systems.

4
src/uas/UAS.h

@ -511,8 +511,10 @@ public slots:
//void setWaypoint(Waypoint* wp); FIXME tbd //void setWaypoint(Waypoint* wp); FIXME tbd
/** @brief Set currently active waypoint */ /** @brief Set currently active waypoint */
//void setWaypointActive(int id); FIXME tbd //void setWaypointActive(int id); FIXME tbd
/** @brief Order the robot to return home / to land on the runway **/ /** @brief Order the robot to return home **/
void home(); void home();
/** @brief Order the robot to land **/
void land();
void halt(); void halt();
void go(); void go();

2
src/uas/UASInterface.h

@ -237,6 +237,8 @@ public slots:
//virtual void setWaypointActive(int wp) = 0; //virtual void setWaypointActive(int wp) = 0;
/** @brief Order the robot to return home / to land on the runway **/ /** @brief Order the robot to return home / to land on the runway **/
virtual void home() = 0; virtual void home() = 0;
/** @brief Order the robot to land **/
virtual void land() = 0;
/** @brief Halt the system */ /** @brief Halt the system */
virtual void halt() = 0; virtual void halt() = 0;
/** @brief Start/continue the current robot action */ /** @brief Start/continue the current robot action */

2
src/ui/uas/UASView.cc

@ -109,7 +109,7 @@ UASView::UASView(UASInterface* uas, QWidget *parent) :
connect(m_ui->liftoffButton, SIGNAL(clicked()), uas, SLOT(launch())); connect(m_ui->liftoffButton, SIGNAL(clicked()), uas, SLOT(launch()));
connect(m_ui->haltButton, SIGNAL(clicked()), uas, SLOT(halt())); connect(m_ui->haltButton, SIGNAL(clicked()), uas, SLOT(halt()));
connect(m_ui->continueButton, SIGNAL(clicked()), uas, SLOT(go())); connect(m_ui->continueButton, SIGNAL(clicked()), uas, SLOT(go()));
connect(m_ui->landButton, SIGNAL(clicked()), uas, SLOT(home())); connect(m_ui->landButton, SIGNAL(clicked()), uas, SLOT(land()));
connect(m_ui->abortButton, SIGNAL(clicked()), uas, SLOT(emergencySTOP())); connect(m_ui->abortButton, SIGNAL(clicked()), uas, SLOT(emergencySTOP()));
connect(m_ui->killButton, SIGNAL(clicked()), uas, SLOT(emergencyKILL())); connect(m_ui->killButton, SIGNAL(clicked()), uas, SLOT(emergencyKILL()));
connect(m_ui->shutdownButton, SIGNAL(clicked()), uas, SLOT(shutdown())); connect(m_ui->shutdownButton, SIGNAL(clicked()), uas, SLOT(shutdown()));

Loading…
Cancel
Save