@ -20,176 +20,162 @@
# include "AppSettings.h"
# include "AppSettings.h"
FollowMe : : FollowMe ( QGCApplication * app , QGCToolbox * toolbox )
FollowMe : : FollowMe ( QGCApplication * app , QGCToolbox * toolbox )
: QGCTool ( app , toolbox ) , estimatation_capabilities ( 0 )
: QGCTool ( app , toolbox )
{
{
memset ( & _motionReport , 0 , sizeof ( motionReport_s ) ) ;
runTime . start ( ) ;
_gcsMotionReportTimer . setSingleShot ( false ) ;
_gcsMotionReportTimer . setSingleShot ( false ) ;
}
}
void FollowMe : : setToolbox ( QGCToolbox * toolbox )
void FollowMe : : setToolbox ( QGCToolbox * toolbox )
{
{
QGCTool : : setToolbox ( toolbox ) ;
QGCTool : : setToolbox ( toolbox ) ;
connect ( & _gcsMotionReportTimer , & QTimer : : timeout , this , & FollowMe : : _sendGCSMotionReport ) ;
connect ( toolbox - > settingsManager ( ) - > appSettings ( ) - > followTarget ( ) , & Fact : : rawValueChanged , this , & FollowMe : : _settingsChanged ) ;
_currentMode = _toolbox - > settingsManager ( ) - > appSettings ( ) - > followTarget ( ) - > rawValue ( ) . toUInt ( ) ;
if ( _currentMode = = MODE_ALWAYS ) {
_enable ( ) ;
}
}
void FollowMe : : followMeHandleManager ( const QString & )
connect ( & _gcsMotionReportTimer , & QTimer : : timeout , this , & FollowMe : : _sendGCSMotionReport ) ;
{
connect ( toolbox - > settingsManager ( ) - > appSettings ( ) - > followTarget ( ) , & Fact : : rawValueChanged , this , & FollowMe : : _settingsChanged ) ;
//-- If we are to change based on current flight mode
if ( _currentMode = = MODE_FOLLOWME ) {
_settingsChanged ( ) ;
QmlObjectListModel & vehicles = * _toolbox - > multiVehicleManager ( ) - > vehicles ( ) ;
for ( int i = 0 ; i < vehicles . count ( ) ; i + + ) {
Vehicle * vehicle = qobject_cast < Vehicle * > ( vehicles [ i ] ) ;
if ( vehicle - > px4Firmware ( ) & & vehicle - > flightMode ( ) . compare ( FirmwarePlugin : : px4FollowMeFlightMode , Qt : : CaseInsensitive ) = = 0 ) {
_enable ( ) ;
return ;
}
}
_disable ( ) ;
}
}
}
void FollowMe : : _settingsChanged ( )
void FollowMe : : _settingsChanged ( )
{
{
uint32_t mode = _toolbox - > settingsManager ( ) - > appSettings ( ) - > followTarget ( ) - > rawValue ( ) . toUInt ( ) ;
_currentMode = _toolbox - > settingsManager ( ) - > appSettings ( ) - > followTarget ( ) - > rawValue ( ) . toUInt ( ) ;
if ( _currentMode ! = mode ) {
_currentMode = mode ;
switch ( _currentMode ) {
switch ( mode ) {
case MODE_NEVER :
case MODE_NEVER :
disconnect ( _toolbox - > multiVehicleManager ( ) , & MultiVehicleManager : : vehicleAdded , this , & FollowMe : : _vehicleAdded ) ;
if ( _gcsMotionReportTimer . isActive ( ) ) {
disconnect ( _toolbox - > multiVehicleManager ( ) , & MultiVehicleManager : : vehicleRemoved , this , & FollowMe : : _vehicleRemoved ) ;
_disable ( ) ;
_disableFollowSend ( ) ;
}
break ;
break ;
case MODE_ALWAYS :
case MODE_ALWAYS :
connect ( _toolbox - > multiVehicleManager ( ) , & MultiVehicleManager : : vehicleAdded , this , & FollowMe : : _vehicleAdded ) ;
if ( ! _gcsMotionReportTimer . isActive ( ) ) {
connect ( _toolbox - > multiVehicleManager ( ) , & MultiVehicleManager : : vehicleRemoved , this , & FollowMe : : _vehicleRemoved ) ;
_enable ( ) ;
_enableFollowSend ( ) ;
}
break ;
break ;
case MODE_FOLLOWME :
case MODE_FOLLOWME :
connect ( _toolbox - > multiVehicleManager ( ) , & MultiVehicleManager : : vehicleAdded , this , & FollowMe : : _vehicleAdded ) ;
if ( ! _gcsMotionReportTimer . isActive ( ) ) {
connect ( _toolbox - > multiVehicleManager ( ) , & MultiVehicleManager : : vehicleRemoved , this , & FollowMe : : _vehicleRemoved ) ;
followMeHandleManager ( QString ( ) ) ;
_enableIfVehicleInFollow ( ) ;
}
break ;
break ;
default :
break ;
}
}
}
}
}
void FollowMe : : _enable ( )
void FollowMe : : _enableFollowSend ( )
{
{
connect ( _toolbox - > qgcPositionManager ( ) ,
if ( ! _gcsMotionReportTimer . isActive ( ) ) {
& QGCPositionManager : : positionInfoUpdated ,
_gcsMotionReportTimer . setInterval ( qMin ( _toolbox - > qgcPositionManager ( ) - > updateInterval ( ) , 250 ) ) ;
this ,
_gcsMotionReportTimer . start ( ) ;
& FollowMe : : _setGPSLocation ) ;
}
_gcsMotionReportTimer . setInterval ( _toolbox - > qgcPositionManager ( ) - > updateInterval ( ) ) ;
_gcsMotionReportTimer . start ( ) ;
}
}
void FollowMe : : _disable ( )
void FollowMe : : _disableFollowSend ( )
{
{
disconnect ( _toolbox - > qgcPositionManager ( ) ,
if ( _gcsMotionReportTimer . isActive ( ) ) {
& QGCPositionManager : : positionInfoUpdated ,
_gcsMotionReportTimer . stop ( ) ;
this ,
}
& FollowMe : : _setGPSLocation ) ;
_gcsMotionReportTimer . stop ( ) ;
}
}
void FollowMe : : _setGPSLocation ( QGeoPositionInfo geoPositionInfo )
void FollowMe : : _sendGCSMotionReport ( )
{
{
QGeoPositionInfo geoPositionInfo = _toolbox - > qgcPositionManager ( ) - > geoPositionInfo ( ) ;
QGeoCoordinate gcsCoordinate = geoPositionInfo . coordinate ( ) ;
if ( ! geoPositionInfo . isValid ( ) ) {
if ( ! geoPositionInfo . isValid ( ) ) {
//-- Invalidate cached coordinates
return ;
memset ( & _motionReport , 0 , sizeof ( motionReport_s ) ) ;
}
} else {
// get the current location coordinates
QGeoCoordinate geoCoordinate = geoPositionInfo . coordinate ( ) ;
GCSMotionReport motionReport = { } ;
uint8_t estimatation_capabilities = 0 ;
_motionReport . lat_int = geoCoordinate . latitude ( ) * 1e7 ;
// get the current location coordinates
_motionReport . lon_int = geoCoordinate . longitude ( ) * 1e7 ;
_motionReport . alt = geoCoordinate . altitude ( ) ;
estimatation_capabilities | = ( 1 < < POS ) ;
motionReport . lat_int = static_cast < int > ( gcsCoordinate . latitude ( ) * 1e7 ) ;
motionReport . lon_int = static_cast < int > ( gcsCoordinate . longitude ( ) * 1e7 ) ;
motionReport . altMetersAMSL = gcsCoordinate . altitude ( ) ;
estimatation_capabilities | = ( 1 < < POS ) ;
// get the current eph and epv
if ( geoPositionInfo . hasAttribute ( QGeoPositionInfo : : Direction ) = = true ) {
motionReport . headingDegrees = geoPositionInfo . attribute ( QGeoPositionInfo : : Direction ) ;
}
if ( geoPositionInfo . hasAttribute ( QGeoPositionInfo : : HorizontalAccuracy ) = = true ) {
// get the current eph and epv
_motionReport . pos_std_dev [ 0 ] = _motionReport . pos_std_dev [ 1 ] = geoPositionInfo . attribute ( QGeoPositionInfo : : HorizontalAccuracy ) ;
}
if ( geoPositionInfo . hasAttribute ( QGeoPositionInfo : : VerticalAccuracy ) = = true ) {
if ( geoPositionInfo . hasAttribute ( QGeoPositionInfo : : HorizontalAccuracy ) ) {
_ motionReport . pos_std_dev [ 2 ] = geoPositionInfo . attribute ( QGeoPositionInfo : : Vertic alAccuracy) ;
motionReport . pos_std_dev [ 0 ] = motionReport . pos_std_dev [ 1 ] = geoPositionInfo . attribute ( QGeoPositionInfo : : Horizont alAccuracy) ;
}
}
// calculate z velocity if it's available
if ( geoPositionInfo . hasAttribute ( QGeoPositionInfo : : VerticalAccuracy ) ) {
motionReport . pos_std_dev [ 2 ] = geoPositionInfo . attribute ( QGeoPositionInfo : : VerticalAccuracy ) ;
}
if ( geoPositionInfo . hasAttribute ( QGeoPositionInfo : : VerticalSpeed ) ) {
// calculate z velocity if it's available
_motionReport . vz = geoPositionInfo . attribute ( QGeoPositionInfo : : VerticalSpeed ) ;
}
if ( geoPositionInfo . hasAttribute ( QGeoPositionInfo : : VerticalSpeed ) ) {
motionReport . vzMetersPerSec = geoPositionInfo . attribute ( QGeoPositionInfo : : VerticalSpeed ) ;
}
// calculate x,y velocity if it's available
// calculate x,y velocity if it's available
if ( ( geoPositionInfo . hasAttribute ( QGeoPositionInfo : : Direction ) = = true ) & &
if ( geoPositionInfo . hasAttribute ( QGeoPositionInfo : : Direction ) & & geoPositionInfo . hasAttribute ( QGeoPositionInfo : : GroundSpeed ) = = true ) {
( geoPositionInfo . hasAttribute ( QGeoPositionInfo : : GroundSpeed ) = = true ) ) {
estimatation_capabilities | = ( 1 < < VEL ) ;
estimatation_capabilities | = ( 1 < < VEL ) ;
qreal direction = _degreesToRadian ( geoPositionInfo . attribute ( QGeoPositionInfo : : Direction ) ) ;
qreal velocity = geoPositionInfo . attribute ( QGeoPositionInfo : : GroundSpeed ) ;
qreal direction = _degreesToRadian ( geoPositionInfo . attribute ( QGeoPositionInfo : : Direction ) ) ;
motionReport . vxMetersPerSec = cos ( direction ) * velocity ;
qreal velocity = geoPositionInfo . attribute ( QGeoPositionInfo : : GroundSpeed ) ;
motionReport . vyMetersPerSec = sin ( direction ) * velocity ;
} else {
motionReport . vxMetersPerSec = 0 ;
motionReport . vyMetersPerSec = 0 ;
}
_motionReport . vx = cos ( direction ) * velocity ;
QmlObjectListModel * vehicles = _toolbox - > multiVehicleManager ( ) - > vehicles ( ) ;
_motionReport . vy = sin ( direction ) * velocity ;
} else {
for ( int i = 0 ; i < vehicles - > count ( ) ; i + + ) {
_motionReport . vx = 0.0f ;
Vehicle * vehicle = vehicles - > value < Vehicle * > ( i ) ;
_motionReport . vy = 0.0f ;
if ( _currentMode = = MODE_ALWAYS | | ( _currentMode = = MODE_FOLLOWME & & _isFollowFlightMode ( vehicle , vehicle - > flightMode ( ) ) ) ) {
vehicle - > firmwarePlugin ( ) - > sendGCSMotionReport ( vehicle , motionReport , estimatation_capabilities ) ;
}
}
}
}
}
}
void FollowMe : : _sendGCSMotionReport ( )
double FollowMe : : _degreesToRadian ( double deg )
{
return deg * M_PI / 180.0 ;
}
void FollowMe : : _vehicleAdded ( Vehicle * vehicle )
{
{
connect ( vehicle , & Vehicle : : flightModeChanged , this , & FollowMe : : _enableIfVehicleInFollow ) ;
_enableIfVehicleInFollow ( ) ;
}
void FollowMe : : _vehicleRemoved ( Vehicle * vehicle )
{
disconnect ( vehicle , & Vehicle : : flightModeChanged , this , & FollowMe : : _enableIfVehicleInFollow ) ;
_enableIfVehicleInFollow ( ) ;
}
//-- Do we have any real data?
void FollowMe : : _enableIfVehicleInFollow ( void )
if ( _motionReport . lat_int = = 0 & & _motionReport . lon_int = = 0 & & _motionReport . alt = = 0 ) {
{
if ( _currentMode = = MODE_ALWAYS ) {
// System always enabled
return ;
return ;
}
}
QmlObjectListModel & vehicles = * _toolbox - > multiVehicleManager ( ) - > vehicles ( ) ;
// Any vehicle in follow mode will enable the system
MAVLinkProtocol * mavlinkProtocol = _toolbox - > mavlinkProtocol ( ) ;
QmlObjectListModel * vehicles = _toolbox - > multiVehicleManager ( ) - > vehicles ( ) ;
mavlink_follow_target_t follow_target ;
memset ( & follow_target , 0 , sizeof ( follow_target ) ) ;
for ( int i = 0 ; i < vehicles - > count ( ) ; i + + ) {
Vehicle * vehicle = vehicles - > value < Vehicle * > ( i ) ;
follow_target . timestamp = runTime . nsecsElapsed ( ) * 1e-6 ;
if ( _isFollowFlightMode ( vehicle , vehicle - > flightMode ( ) ) ) {
follow_target . est_capabilities = estimatation_capabilities ;
_enableFollowSend ( ) ;
follow_target . position_cov [ 0 ] = _motionReport . pos_std_dev [ 0 ] ;
return ;
follow_target . position_cov [ 2 ] = _motionReport . pos_std_dev [ 2 ] ;
follow_target . alt = _motionReport . alt ;
follow_target . lat = _motionReport . lat_int ;
follow_target . lon = _motionReport . lon_int ;
follow_target . vel [ 0 ] = _motionReport . vx ;
follow_target . vel [ 1 ] = _motionReport . vy ;
for ( int i = 0 ; i < vehicles . count ( ) ; i + + ) {
Vehicle * vehicle = qobject_cast < Vehicle * > ( vehicles [ i ] ) ;
if ( _currentMode | | vehicle - > flightMode ( ) . compare ( FirmwarePlugin : : px4FollowMeFlightMode , Qt : : CaseInsensitive ) = = 0 ) {
mavlink_message_t message ;
mavlink_msg_follow_target_encode_chan ( mavlinkProtocol - > getSystemId ( ) ,
mavlinkProtocol - > getComponentId ( ) ,
vehicle - > priorityLink ( ) - > mavlinkChannel ( ) ,
& message ,
& follow_target ) ;
vehicle - > sendMessageOnLink ( vehicle - > priorityLink ( ) , message ) ;
}
}
}
}
_disableFollowSend ( ) ;
}
}
dou ble FollowMe : : _degreesToRadian ( double deg )
bool FollowMe : : _isFollowFlightMode ( Vehicle * vehicle , const QString & flightMode )
{
{
return deg * M_PI / 180. 0;
return flightMode . compare ( vehicle - > followFlightMode ( ) ) = = 0 ;
}
}