Commit 0641f7f2 authored by Don Gagne's avatar Don Gagne
Browse files

Removing unused code

parent 69d14982
......@@ -201,11 +201,8 @@ FORMS += \
src/ui/uas/UASMessageView.ui \
src/ui/uas/UASQuickView.ui \
src/ui/uas/UASQuickViewItemSelect.ui \
src/ui/UASControl.ui \
src/ui/UASInfo.ui \
src/ui/UASList.ui \
src/ui/UASRawStatusView.ui \
src/ui/UASView.ui \
src/ui/WaypointEditableView.ui \
src/ui/WaypointList.ui \
src/ui/WaypointViewOnlyView.ui \
......@@ -322,16 +319,13 @@ HEADERS += \
src/ui/SettingsDialog.h \
src/ui/toolbar/MainToolBar.h \
src/ui/uas/QGCUnconnectedInfoWidget.h \
src/ui/uas/UASControlWidget.h \
src/ui/uas/UASInfoWidget.h \
src/ui/uas/UASListWidget.h \
src/ui/uas/UASMessageView.h \
src/ui/uas/UASQuickView.h \
src/ui/uas/UASQuickViewGaugeItem.h \
src/ui/uas/UASQuickViewItem.h \
src/ui/uas/UASQuickViewItemSelect.h \
src/ui/uas/UASQuickViewTextItem.h \
src/ui/uas/UASView.h \
src/ui/UASRawStatusView.h \
src/ui/WaypointEditableView.h \
src/ui/WaypointList.h \
......@@ -452,16 +446,13 @@ SOURCES += \
src/ui/SettingsDialog.cc \
src/ui/toolbar/MainToolBar.cc \
src/ui/uas/QGCUnconnectedInfoWidget.cc \
src/ui/uas/UASControlWidget.cc \
src/ui/uas/UASInfoWidget.cc \
src/ui/uas/UASListWidget.cc \
src/ui/uas/UASMessageView.cc \
src/ui/uas/UASQuickView.cc \
src/ui/uas/UASQuickViewGaugeItem.cc \
src/ui/uas/UASQuickViewItem.cc \
src/ui/uas/UASQuickViewItemSelect.cc \
src/ui/uas/UASQuickViewTextItem.cc \
src/ui/uas/UASView.cc \
src/ui/UASRawStatusView.cpp \
src/ui/WaypointEditableView.cc \
src/ui/WaypointList.cc \
......
This diff is collapsed.
......@@ -72,10 +72,6 @@ public:
/** @brief The name of the robot */
QString getUASName(void) const;
/** @brief Get short state */
const QString& getShortState() const;
/** @brief Get short mode */
const QString& getShortMode() const;
/** @brief Get the unique system id */
int getUASID() const;
/** @brief Get the airframe */
......@@ -319,17 +315,6 @@ public:
return yaw;
}
QVector3D getNedPosGlobalOffset() const
{
return nedPosGlobalOffset;
}
QVector3D getNedAttGlobalOffset() const
{
return nedAttGlobalOffset;
}
// Setters for HIL noise variance
void setXaccVar(float var){
xacc_var = var;
......@@ -406,20 +391,9 @@ protected: //COMMENTS FOR TEST UNIT
unsigned char type; ///< UAS type (from type enum)
int airframe; ///< The airframe type
int autopilot; ///< Type of the Autopilot: -1: None, 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
bool systemIsArmed; ///< If the system is armed
uint8_t base_mode; ///< The current mode of the MAV
uint32_t custom_mode; ///< The current mode of the MAV
int status; ///< The current status of the MAV
QString shortModeText; ///< Short textual mode description
QString shortStateText; ///< Short textual state description
/// OUTPUT
QList<double> actuatorValues;
QList<QString> actuatorNames;
QList<double> motorValues;
QList<QString> motorNames;
double thrustSum; ///< Sum of forward/up thrust of all thrust actuators, in Newtons
double thrustMax; ///< Maximum forward/up thrust of this vehicle, in Newtons
// dongfang: This looks like a candidate for being moved off to a separate class.
/// BATTERY / ENERGY
......@@ -433,7 +407,6 @@ protected: //COMMENTS FOR TEST UNIT
double currentCurrent; ///< Battery current currently measured
bool batteryRemainingEstimateEnabled; ///< If the estimate is enabled, QGC will try to estimate the remaining battery life
float chargeLevel; ///< Charge level of battery, in percent
int timeRemaining; ///< Remaining time calculated based on previous and current
bool lowBattAlarm; ///< Switch if battery is low
......@@ -477,9 +450,6 @@ protected: //COMMENTS FOR TEST UNIT
double speedY; ///< True speed in Y axis
double speedZ; ///< True speed in Z axis
QVector3D nedPosGlobalOffset; ///< Offset between the system's NED position measurements and the swarm / global 0/0/0 origin
QVector3D nedAttGlobalOffset; ///< Offset between the system's NED position measurements and the swarm / global 0/0/0 origin
/// WAYPOINT NAVIGATION
double distToWaypoint; ///< Distance to next waypoint
double airSpeed; ///< Airspeed
......@@ -534,20 +504,10 @@ protected: //COMMENTS FOR TEST UNIT
public:
/** @brief Set the current battery type */
void setBattery(BatteryType type, int cells);
/** @brief Estimate how much flight time is remaining */
int calculateTimeRemaining();
/** @brief Get the current charge level */
float getChargeLevel();
/** @brief Get the human-readable status message for this code */
void getStatusForCode(int statusCode, QString& uasState, QString& stateDescription);
/** @brief Check if vehicle is in autonomous mode */
bool isAuto();
/** @brief Check if vehicle is armed */
bool isArmed() const { return systemIsArmed; }
/** @brief Check if vehicle is supposed to be in HIL mode by the GS */
bool isHilEnabled() const { return hilEnabled; }
/** @brief Check if vehicle is in HIL mode */
bool isHilActive() const { return base_mode & MAV_MODE_FLAG_HIL_ENABLED; }
/** @brief Get reference to the waypoint manager **/
UASWaypointManager* getWaypointManager() {
......@@ -568,155 +528,11 @@ public:
int getSystemType();
bool isAirplane();
/**
* @brief Returns true for systems that can reverse. If the system has no control over position, it returns false as
* @return If the specified vehicle type can
*/
bool systemCanReverse() const
{
switch(type)
{
case MAV_TYPE_GENERIC:
case MAV_TYPE_FIXED_WING:
case MAV_TYPE_ROCKET:
case MAV_TYPE_FLAPPING_WING:
// System types that don't have movement
case MAV_TYPE_ANTENNA_TRACKER:
case MAV_TYPE_GCS:
case MAV_TYPE_FREE_BALLOON:
default:
return false;
case MAV_TYPE_QUADROTOR:
case MAV_TYPE_COAXIAL:
case MAV_TYPE_HELICOPTER:
case MAV_TYPE_AIRSHIP:
case MAV_TYPE_GROUND_ROVER:
case MAV_TYPE_SURFACE_BOAT:
case MAV_TYPE_SUBMARINE:
case MAV_TYPE_HEXAROTOR:
case MAV_TYPE_OCTOROTOR:
case MAV_TYPE_TRICOPTER:
return true;
}
}
QString getSystemTypeName()
{
switch(type)
{
case MAV_TYPE_GENERIC:
return "GENERIC";
break;
case MAV_TYPE_FIXED_WING:
return "FIXED_WING";
break;
case MAV_TYPE_QUADROTOR:
return "QUADROTOR";
break;
case MAV_TYPE_COAXIAL:
return "COAXIAL";
break;
case MAV_TYPE_HELICOPTER:
return "HELICOPTER";
break;
case MAV_TYPE_ANTENNA_TRACKER:
return "ANTENNA_TRACKER";
break;
case MAV_TYPE_GCS:
return "GCS";
break;
case MAV_TYPE_AIRSHIP:
return "AIRSHIP";
break;
case MAV_TYPE_FREE_BALLOON:
return "FREE_BALLOON";
break;
case MAV_TYPE_ROCKET:
return "ROCKET";
break;
case MAV_TYPE_GROUND_ROVER:
return "GROUND_ROVER";
break;
case MAV_TYPE_SURFACE_BOAT:
return "BOAT";
break;
case MAV_TYPE_SUBMARINE:
return "SUBMARINE";
break;
case MAV_TYPE_HEXAROTOR:
return "HEXAROTOR";
break;
case MAV_TYPE_OCTOROTOR:
return "OCTOROTOR";
break;
case MAV_TYPE_TRICOPTER:
return "TRICOPTER";
break;
case MAV_TYPE_FLAPPING_WING:
return "FLAPPING_WING";
break;
default:
return "";
break;
}
}
QImage getImage();
void requestImage();
int getAutopilotType(){
return autopilot;
}
QString getAutopilotTypeName()
{
switch (autopilot)
{
case MAV_AUTOPILOT_GENERIC:
return "GENERIC";
break;
case MAV_AUTOPILOT_SLUGS:
return "SLUGS";
break;
case MAV_AUTOPILOT_ARDUPILOTMEGA:
return "ARDUPILOTMEGA";
break;
case MAV_AUTOPILOT_OPENPILOT:
return "OPENPILOT";
break;
case MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY:
return "GENERIC_WAYPOINTS_ONLY";
break;
case MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY:
return "GENERIC_MISSION_NAVIGATION_ONLY";
break;
case MAV_AUTOPILOT_GENERIC_MISSION_FULL:
return "GENERIC_MISSION_FULL";
break;
case MAV_AUTOPILOT_INVALID:
return "NO AP";
break;
case MAV_AUTOPILOT_PPZ:
return "PPZ";
break;
case MAV_AUTOPILOT_UDB:
return "UDB";
break;
case MAV_AUTOPILOT_FP:
return "FP";
break;
case MAV_AUTOPILOT_PX4:
return "PX4";
break;
default:
return "UNKNOWN";
break;
}
}
/** From UASInterface */
QList<QAction*> getActions() const
{
return actions;
}
public slots:
/** @brief Set the autopilot type */
......@@ -737,35 +553,12 @@ public slots:
}
}
/** @brief Set a new name **/
void setUASName(const QString& name);
/** @brief Executes a command **/
void executeCommand(MAV_CMD command);
/** @brief Executes a command with 7 params */
void executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7, int component);
/** @brief Executes a command ack, with success boolean **/
void executeCommandAck(int num, bool success);
/** @brief Set the current battery type and voltages */
void setBatterySpecs(const QString& specs);
/** @brief Get the current battery type and specs */
QString getBatterySpecs();
/** @brief Launches the system **/
void launch();
/** @brief Write this waypoint to the list of waypoints */
//void setWaypoint(MissionItem* wp); FIXME tbd
/** @brief Set currently active waypoint */
//void setWaypointActive(int id); FIXME tbd
/** @brief Order the robot to return home **/
void home();
/** @brief Order the robot to land **/
void land();
/** @brief Order the robot to pair its receiver **/
void pairRX(int rxType, int rxSubType);
void halt();
void go();
/** @brief Enable / disable HIL */
#ifndef __mobile__
void enableHilFlightGear(bool enable, QString options, bool sensorHil, QObject * configuration);
......@@ -813,40 +606,9 @@ public slots:
void stopHil();
#endif
/** @brief Stops the robot system. If it is an MAV, the robot starts the emergency landing procedure **/
void emergencySTOP();
/** @brief Kills the robot. All systems are immediately shut down (e.g. the main power line is cut). This might lead to a crash **/
bool emergencyKILL();
/** @brief Shut the system cleanly down. Will shut down any onboard computers **/
void shutdown();
/** @brief Set the target position for the robot to navigate to. */
void setTargetPosition(float x, float y, float z, float yaw);
void startLowBattAlarm();
void stopLowBattAlarm();
/** @brief Arm system */
void armSystem();
/** @brief Disable the motors */
void disarmSystem();
/** @brief Toggle the armed state of the system. */
void toggleArmedState();
/**
* @brief Tell the UAS to switch into a completely-autonomous mode, so disable manual input.
*/
void goAutonomous();
/**
* @brief Tell the UAS to switch to manual control. Stabilized attitude may simultaneously be engaged.
*/
void goManual();
/**
* @brief Tell the UAS to switch between manual and autonomous control.
*/
void toggleAutonomy();
/** @brief Set the values for the manual control of the vehicle */
#ifndef __mobile__
void setExternalControlSetpoint(float roll, float pitch, float yaw, float thrust, quint16 buttons, int joystickMode);
......@@ -860,39 +622,11 @@ public slots:
/** @brief Receive a message from one of the communication links. */
virtual void receiveMessage(mavlink_message_t message);
#ifdef QGC_PROTOBUF_ENABLED
/** @brief Receive a message from one of the communication links. */
virtual void receiveExtendedMessage(LinkInterface* link, std::tr1::shared_ptr<google::protobuf::Message> message);
#endif
/** @brief Set current mode of operation, e.g. auto or manual, always uses the current arming status for safety reason */
void setMode(uint8_t newBaseMode, uint32_t newCustomMode);
/** @brief Set current mode of operation, e.g. auto or manual, does not check the arming status, for anything else than arming/disarming operations use setMode instead */
void setModeArm(uint8_t newBaseMode, uint32_t newCustomMode);
void enableAllDataTransmission(int rate);
void enableRawSensorDataTransmission(int rate);
void enableExtendedSystemStatusTransmission(int rate);
void enableRCChannelDataTransmission(int rate);
void enableRawControllerDataTransmission(int rate);
//void enableRawSensorFusionTransmission(int rate);
void enablePositionTransmission(int rate);
void enableExtra1Transmission(int rate);
void enableExtra2Transmission(int rate);
void enableExtra3Transmission(int rate);
/** @brief Update the system state */
void updateState();
/** @brief Set world frame origin at current GPS position */
void setLocalOriginAtCurrentGPSPosition();
/** @brief Set world frame origin / home position at this GPS position */
void setHomePosition(double lat, double lon, double alt);
/** @brief Set local position setpoint */
void setLocalPositionSetpoint(float x, float y, float z, float yaw);
/** @brief Add an offset in body frame to the setpoint */
void setLocalPositionOffset(float x, float y, float z, float yaw);
void startCalibration(StartCalibrationType calType);
void stopCalibration(void);
......@@ -900,27 +634,12 @@ public slots:
void startBusConfig(StartBusConfigType calType);
void stopBusConfig(void);
void startDataRecording();
void stopDataRecording();
void deleteSettings();
/** @brief Triggers the action associated with the given ID. */
void triggerAction(int action);
/** @brief Send command to map a RC channel to a parameter */
void sendMapRCToParam(QString param_id, float scale, float value0, quint8 param_rc_channel_index, float valueMin, float valueMax);
/** @brief Send command to disable all bindings/maps between RC and parameters */
void unsetRCToParameterMap();
signals:
/** @brief The main/battery voltage has changed/was updated */
//void voltageChanged(int uasId, double voltage); // Defined in UASInterface already
/** @brief An actuator value has changed */
//void actuatorChanged(UASInterface*, int actId, double value); // Defined in UASInterface already
/** @brief An actuator value has changed */
void actuatorChanged(UASInterface* uas, QString actuatorName, double min, double max, double value);
void motorChanged(UASInterface* uas, QString motorName, double min, double max, double value);
/** @brief The system load (MCU/CPU usage) changed */
void loadChanged(UASInterface* uas, double load);
/** @brief Propagate a heartbeat received from the system */
//void heartbeat(UASInterface* uas); // Defined in UASInterface already
......@@ -966,13 +685,11 @@ protected:
quint64 lastVoltageWarning; ///< Time at which the last voltage warning occured
quint64 lastNonNullTime; ///< The last timestamp from the MAV that was not null
unsigned int onboardTimeOffsetInvalidCount; ///< Count when the offboard time offset estimation seemed wrong
bool hilEnabled; ///< Set to true if HIL mode is enabled from GCS (UAS might be in HIL even if this flag is not set, this defines the GCS HIL setting)
bool hilEnabled;
bool sensorHil; ///< True if sensor HIL is enabled
quint64 lastSendTimeGPS; ///< Last HIL GPS message sent
quint64 lastSendTimeSensors; ///< Last HIL Sensors message sent
quint64 lastSendTimeOpticalFlow; ///< Last HIL Optical Flow message sent
QList<QAction*> actions; ///< A list of actions that this UAS can perform.
protected slots:
/** @brief Write settings to disk */
......
......@@ -54,32 +54,6 @@ enum BatteryType
AGZN = 5
}; ///< The type of battery used
/*
enum SpeedMeasurementSource
{
PRIMARY_SPEED = 0, // ArduPlane: Measured airspeed or estimated airspeed. ArduCopter: Ground (XY) speed.
GROUNDSPEED_BY_UAV = 1, // Ground speed as reported by UAS
GROUNDSPEED_BY_GPS = 2, // Ground speed as calculated from received GPS velocity data
LOCAL_SPEED = 3
}; ///< For velocity data, the data source
enum AltitudeMeasurementSource
{
PRIMARY_ALTITUDE = 0, // ArduPlane: air and ground speed mix. This is the altitude used for navigastion.
BAROMETRIC_ALTITUDE = 1, // Altitude is pressure altitude. Ardupilot reports no altitude purely by barometer,
// however when ALT_MIX==1, mix-altitude is purely barometric.
GPS_ALTITUDE = 2 // GPS ASL altitude
}; ///< For altitude data, the data source
// TODO!!! The different frames are probably represented elsewhere. There should really only
// be one set of frames. We also need to keep track of the home alt. somehow.
enum AltitudeMeasurementFrame
{
ABSOLUTE = 0, // Altitude is pressure altitude
ABOVE_HOME_POSITION = 1
}; ///< For altitude data, a reference frame
*/
/**
* @brief Interface for all robots.
*
......@@ -96,11 +70,6 @@ public:
/** @brief The name of the robot **/
virtual QString getUASName() const = 0;
/** @brief Get short state */
virtual const QString& getShortState() const = 0;
/** @brief Get short mode */
virtual const QString& getShortMode() const = 0;
//virtual QColor getColor() = 0;
virtual int getUASID() const = 0; ///< Get the ID of the connected UAS
/** @brief The time interval the robot is switched on **/
virtual quint64 getUptime() const = 0;
......@@ -120,8 +89,6 @@ public:
virtual double getPitch() const = 0;
virtual double getYaw() const = 0;
virtual bool isArmed() const = 0;
/** @brief Set the airframe of this MAV */
virtual int getAirframe() const = 0;
......@@ -192,15 +159,9 @@ public:
virtual int getSystemType() = 0;
/** @brief Is it an airplane (or like one)?,..)*/
virtual bool isAirplane() = 0;
/** @brief Indicates whether this system is capable of controlling a reverse velocity.
* Used for, among other things, altering joystick input to either -1:1 or 0:1 range.
*/
virtual bool systemCanReverse() const = 0;
virtual QString getSystemTypeName() = 0;
/** @brief Get the type of the autopilot (PIXHAWK, APM, UDB, PPZ,..) */
virtual int getAutopilotType() = 0;
virtual QString getAutopilotTypeName() = 0;
virtual void setAutopilotType(int apType) = 0;
virtual QMap<int, QString> getComponents() = 0;
......@@ -210,13 +171,6 @@ public:
return color;
}
/** @brief Returns a list of actions/commands that this vehicle can perform.
* Used for creating UI elements for built-in functionality for this vehicle.
* Actions should be mappings to `void f(void);` functions that simply issue
* a command to the vehicle.
*/
virtual QList<QAction*> getActions() const = 0;
static const unsigned int WAYPOINT_RADIUS_DEFAULT_FIXED_WING = 25;
static const unsigned int WAYPOINT_RADIUS_DEFAULT_ROTARY_WING = 5;
......@@ -250,86 +204,22 @@ public:
public slots:
/** @brief Set a new name for the system */
virtual void setUASName(const QString& name) = 0;
/** @brief Execute command immediately **/
virtual void executeCommand(MAV_CMD command) = 0;
/** @brief Executes a command **/
virtual void executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7, int component) = 0;
/** @brief Executes a command ack, with success boolean **/
virtual void executeCommandAck(int num, bool success) = 0;
/** @brief Selects the airframe */
virtual void setAirframe(int airframe) = 0;
/** @brief Launches the system/Liftof **/
virtual void launch() = 0;
/** @brief Set a new waypoint **/
//virtual void setWaypoint(MissionItem* wp) = 0;
/** @brief Set this waypoint as next waypoint to fly to */
//virtual void setWaypointActive(int wp) = 0;
/** @brief Order the robot to return home / to land on the runway **/
virtual void home() = 0;
/** @brief Order the robot to land **/
virtual void land() = 0;
/** @brief Order the robot to pair its receiver **/
virtual void pairRX(int rxType, int rxSubType) = 0;
/** @brief Halt the system */
virtual void halt() = 0;
/** @brief Start/continue the current robot action */
virtual void go() = 0;
/** @brief Set the current mode of operation */
virtual void setMode(uint8_t newBaseMode, uint32_t newCustomMode) = 0;
/** Stops the robot system. If it is an MAV, the robot starts the emergency landing procedure **/
virtual void emergencySTOP() = 0;
/** Kills the robot. All systems are immediately shut down (e.g. the main power line is cut). This might lead to a crash **/
virtual bool emergencyKILL() = 0;
/**
* @brief Shut down the system's computers
*
* Works only if already landed and will cleanly shut down all onboard computers.
*/
virtual void shutdown() = 0;
/** @brief Set the target position for the robot to navigate to.
* @param x x-coordinate of the target position
* @param y y-coordinate of the target position
* @param z z-coordinate of the target position
* @param yaw heading of the target position
*/
virtual void setTargetPosition(float x, float y, float z, float yaw) = 0;
/** @brief Request the list of stored waypoints from the robot */
//virtual void requestWaypoints() = 0;
/** @brief Clear all existing waypoints on the robot */
//virtual void clearWaypointList() = 0;
/** @brief Set world frame origin at current GPS position */
virtual void setLocalOriginAtCurrentGPSPosition() = 0;
/** @brief Set world frame origin / home position at this GPS position */
virtual void setHomePosition(double lat, double lon, double alt) = 0;
virtual void enableAllDataTransmission(int rate) = 0;
virtual void enableRawSensorDataTransmission(int rate) = 0;
virtual void enableExtendedSystemStatusTransmission(int rate) = 0;
virtual void enableRCChannelDataTransmission(int rate) = 0;
virtual void enableRawControllerDataTransmission(int rate) = 0;
//virtual void enableRawSensorFusionTransmission(int rate) = 0;
virtual void enablePositionTransmission(int rate) = 0;
virtual void enableExtra1Transmission(int rate) = 0;
virtual void enableExtra2Transmission(int rate) = 0;
virtual void enableExtra3Transmission(int rate) = 0;
virtual void setLocalPositionSetpoint(float x, float y, float z, float yaw) = 0;
virtual void setLocalPositionOffset(float x, float y, float z, float yaw) = 0;
virtual void setHomePosition(double lat, double lon, double alt) = 0;
/** @brief Return if this a rotary wing */
virtual bool isRotaryWing() = 0;
/** @brief Return if this is a fixed wing */
virtual bool isFixedWing() = 0;
/** @brief Set the current battery type and voltages */
virtual void setBatterySpecs(const QString& specs) = 0;
/** @brief Get the current battery type and specs */
virtual QString getBatterySpecs() = 0;
/** @brief Send the full HIL state to the MAV */
#ifndef __mobile__
virtual void sendHilState(quint64 time_us, float roll, float pitch, float yaw, float rollspeed,
......@@ -360,8 +250,6 @@ protected:
signals:
/** @brief The robot state has changed */
void statusChanged(int stateFlag);
/** @brief A new component was detected or created */
void componentCreated(int uas, int component, const QString& name);
/** @brief The robot state has changed
*
* @param uas this robot
......@@ -369,32 +257,10 @@ signals:
* @param description longer textual description. Should be however limited to a short text, e.g. 200 chars.
*/
void statusChanged(UASInterface* uas, QString status, QString description);
/**
* @brief Received a plain text message from the robot
* This signal should NOT be used for standard communication, but rather for VERY IMPORTANT
* messages like critical errors.
*
* @param uasid ID of the sending system
* @param compid ID of the sending component
* @param text the status text
* @param severity The severity of the message, 0 for plain debug messages, 10 for very critical messages
*/
void poiFound(UASInterface* uas, int type, int colorIndex, QString message, float x, float y, float z);
void poiConnectionFound(UASInterface* uas, int type, int colorIndex, QString message, float x1, float y1, float z1, float x2, float y2, float z2);
/** @brief A text message from the system has been received */
void textMessageReceived(int uasid, int componentid, int severity, QString text);
void navModeChanged(int uasid, int mode, const QString& text);
/** @brief System is now armed */
void armed();
/** @brief System is now disarmed */
void disarmed();
/** @brief Arming mode changed */
void armingChanged(bool armed);
/**
* @brief Update the error count of a device
*
......@@ -417,22 +283,10 @@ signals:
* @param receiveDrop drop rate of packets this MAV receives (sent from GCS or other MAVs)
*/
void dropRateChanged(int systemId, float receiveDrop);
/** @brief Robot mode has changed */
void modeChanged(int sysId, QString status, QString description);
/** @brief A command has been issued **/
void commandSent(int command);
/** @brief The robot is connecting **/
void connecting();
/** @brief The robot is connected **/
void connected();
/** @brief The robot is disconnected **/
void disconnected();
/** @brief The robot is active **/
void activated();
/** @brief The robot is inactive **/
void deactivated();
/** @brief The robot is manually controlled **/
void manualControl();
/** @brief A value of the robot has changed.
*
......@@ -448,12 +302,8 @@ signals:
*/
void valueChanged(const int uasid, const QString& name, const QString& unit, const QVariant &value,const quint64 msecs);
void voltageChanged(int uasId, double voltage);
void waypointUpdated(int uasId, int id, double x, double y, double z, double yaw, bool autocontinue, bool active);
void waypointSelected(int uasId, int id);
void waypointReached(UASInterface* uas, int id);
void autoModeChanged(bool autoMode);
void parameterUpdate(int uas, int component, QString parameterName, int parameterCount, int parameterId, int type, QVariant value);
/**
* @brief The battery status has been updated
*
......@@ -465,7 +315,6 @@ signals:
void batteryChanged(UASInterface* uas, double voltage, double current, double percent, int seconds);
void batteryConsumedChanged(UASInterface* uas, double current_consumed);
void statusChanged(UASInterface* uas, QString status);
void actuatorChanged(UASInterface*, int actId, double value);
void thrustChanged(UASInterface*, double thrust);
void heartbeat(UASInterface* uas);
void attitudeChanged(UASInterface*, double roll, double pitch, double yaw, quint64 usec);
......@@ -520,13 +369,6 @@ signals:
void baroStatusChanged(bool supported, bool enabled, bool ok);
/** @brief Differential pressure / airspeed status changed */
void airspeedStatusChanged(bool supported, bool enabled, bool ok);
/** @brief Actuator status changed */
void actuatorStatusChanged(bool supported, bool enabled, bool ok);
/** @brief Laser scanner status changed */
void laserStatusChanged(bool supported, bool enabled, bool ok);
/** @brief Vicon / Leica Geotracker status changed */
void groundTruthSensorStatusChanged(bool supported, bool enabled, bool ok);
/** @brief Value of a remote control channel (raw) */
void remoteControlChannelRawChanged(int channelId, float raw);
......@@ -540,21 +382,6 @@ signals:
* @param fix 0: lost, 1: 2D local position hold, 2: 2D localization, 3: 3D localization
*/
void localizationChanged(UASInterface* uas, int fix);
/**
* @brief GPS localization quality changed
* @param fix 0: lost, 1: at least one satellite, but no GPS fix, 2: 2D localization, 3: 3D localization
*/
void gpsLocalizationChanged(UASInterface* uas, int fix);
/**
* @brief Vision localization quality changed
* @param fix 0: lost, 1: 2D local position hold, 2: 2D localization, 3: 3D localization
*/
void visionLocalizationChanged(UASInterface* uas, int fix);
/**
* @brief IR/U localization quality changed
* @param fix 0: No IR/Ultrasound sensor, N > 0: Found N active sensors
*/
void irUltraSoundLocalizationChanged(UASInterface* uas, int fix);
// ERROR AND STATUS SIGNALS
/** @brief Heartbeat timed out or was regained */
......@@ -564,16 +391,9 @@ signals:
/** @brief Core specifications have changed */
void systemSpecsChanged(int uasId);
/** @brief Object detected */
void objectDetected(unsigned int time, int id, int type, const QString& name, int quality, float bearing, float distance);
// HOME POSITION / ORIGIN CHANGES
void homePositionChanged(int uas, double lat, double lon, double alt);
/** @brief The system received an unknown message, which it could not interpret */
void unknownPacketReceived(int uas, int component, int messageid);
protected:
// TIMEOUT CONSTANTS
......
Supports Markdown
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