@ -451,7 +451,7 @@ private:
@@ -451,7 +451,7 @@ private:
namespace
{
PX4IO * g_dev ;
PX4IO * g_dev = nullptr ;
}
@ -780,8 +780,6 @@ PX4IO::task_main()
@@ -780,8 +780,6 @@ PX4IO::task_main()
hrt_abstime poll_last = 0 ;
hrt_abstime orb_check_last = 0 ;
log ( " starting " ) ;
_thread_mavlink_fd = : : open ( MAVLINK_LOG_DEVICE , 0 ) ;
/*
@ -815,8 +813,6 @@ PX4IO::task_main()
@@ -815,8 +813,6 @@ PX4IO::task_main()
fds [ 0 ] . fd = _t_actuator_controls_0 ;
fds [ 0 ] . events = POLLIN ;
log ( " ready " ) ;
/* lock against the ioctl handler */
lock ( ) ;
@ -1679,7 +1675,18 @@ PX4IO::mixer_send(const char *buf, unsigned buflen, unsigned retries)
@@ -1679,7 +1675,18 @@ PX4IO::mixer_send(const char *buf, unsigned buflen, unsigned retries)
total_len + + ;
}
int ret = io_reg_set ( PX4IO_PAGE_MIXERLOAD , 0 , ( uint16_t * ) frame , total_len / 2 ) ;
int ret ;
for ( int i = 0 ; i < 30 ; i + + ) {
/* failed, but give it a 2nd shot */
ret = io_reg_set ( PX4IO_PAGE_MIXERLOAD , 0 , ( uint16_t * ) frame , total_len / 2 ) ;
if ( ret ) {
usleep ( 333 ) ;
} else {
break ;
}
}
/* print mixer chunk */
if ( debuglevel > 5 | | ret ) {
@ -1703,7 +1710,18 @@ PX4IO::mixer_send(const char *buf, unsigned buflen, unsigned retries)
@@ -1703,7 +1710,18 @@ PX4IO::mixer_send(const char *buf, unsigned buflen, unsigned retries)
msg - > text [ 0 ] = ' \n ' ;
msg - > text [ 1 ] = ' \0 ' ;
int ret = io_reg_set ( PX4IO_PAGE_MIXERLOAD , 0 , ( uint16_t * ) frame , ( sizeof ( px4io_mixdata ) + 2 ) / 2 ) ;
int ret ;
for ( int i = 0 ; i < 30 ; i + + ) {
/* failed, but give it a 2nd shot */
ret = io_reg_set ( PX4IO_PAGE_MIXERLOAD , 0 , ( uint16_t * ) frame , ( sizeof ( px4io_mixdata ) + 2 ) / 2 ) ;
if ( ret ) {
usleep ( 333 ) ;
} else {
break ;
}
}
if ( ret )
return ret ;
@ -2705,6 +2723,7 @@ px4io_main(int argc, char *argv[])
@@ -2705,6 +2723,7 @@ px4io_main(int argc, char *argv[])
printf ( " [px4io] loaded, detaching first \n " ) ;
/* stop the driver */
delete g_dev ;
g_dev = nullptr ;
}
PX4IO_Uploader * up ;
@ -2788,10 +2807,6 @@ px4io_main(int argc, char *argv[])
@@ -2788,10 +2807,6 @@ px4io_main(int argc, char *argv[])
delete interface ;
errx ( 1 , " driver alloc failed " ) ;
}
if ( OK ! = g_dev - > init ( ) ) {
warnx ( " driver init failed, still trying.. " ) ;
}
}
uint16_t arg = atol ( argv [ 2 ] ) ;
@ -2803,6 +2818,7 @@ px4io_main(int argc, char *argv[])
@@ -2803,6 +2818,7 @@ px4io_main(int argc, char *argv[])
// tear down the px4io instance
delete g_dev ;
g_dev = nullptr ;
// upload the specified firmware
const char * fn [ 2 ] ;
@ -2861,6 +2877,7 @@ px4io_main(int argc, char *argv[])
@@ -2861,6 +2877,7 @@ px4io_main(int argc, char *argv[])
/* stop the driver */
delete g_dev ;
g_dev = nullptr ;
exit ( 0 ) ;
}