Merge branch 'master' into cmake-2

This commit is contained in:
Lorenz Meier 2015-09-27 14:23:00 +02:00
commit a4e56abd71
5 changed files with 63 additions and 32 deletions

View File

@ -159,7 +159,14 @@ void UavcanBarometerBridge::air_pressure_sub_cb(const
{ {
baro_report report; baro_report report;
report.timestamp = msg.getMonotonicTimestamp().toUSec(); /*
* FIXME HACK
* This code used to rely on msg.getMonotonicTimestamp().toUSec() instead of HRT.
* It stopped working when the time sync feature has been introduced, because it caused libuavcan
* to use an independent time source (based on hardware TIM5) instead of HRT.
* The proper solution is to be developed.
*/
report.timestamp = hrt_absolute_time();
report.temperature = last_temperature_kelvin - 273.15F; report.temperature = last_temperature_kelvin - 273.15F;
report.pressure = msg.static_pressure / 100.0F; // Convert to millibar report.pressure = msg.static_pressure / 100.0F; // Convert to millibar
report.error_count = 0; report.error_count = 0;

View File

@ -96,7 +96,15 @@ void UavcanGnssBridge::gnss_fix_sub_cb(const uavcan::ReceivedDataStructure<uavca
auto report = ::vehicle_gps_position_s(); auto report = ::vehicle_gps_position_s();
report.timestamp_position = msg.getMonotonicTimestamp().toUSec(); /*
* FIXME HACK
* There used to be the following line of code:
* report.timestamp_position = msg.getMonotonicTimestamp().toUSec();
* It stopped working when the time sync feature has been introduced, because it caused libuavcan
* to use an independent time source (based on hardware TIM5) instead of HRT.
* The proper solution is to be developed.
*/
report.timestamp_position = hrt_absolute_time();
report.lat = msg.latitude_deg_1e8 / 10; report.lat = msg.latitude_deg_1e8 / 10;
report.lon = msg.longitude_deg_1e8 / 10; report.lon = msg.longitude_deg_1e8 / 10;
report.alt = msg.height_msl_mm; report.alt = msg.height_msl_mm;

View File

@ -146,7 +146,14 @@ void UavcanMagnetometerBridge::mag_sub_cb(const uavcan::ReceivedDataStructure<ua
{ {
lock(); lock();
_report.range_ga = 1.3F; // Arbitrary number, doesn't really mean anything _report.range_ga = 1.3F; // Arbitrary number, doesn't really mean anything
_report.timestamp = msg.getMonotonicTimestamp().toUSec(); /*
* FIXME HACK
* This code used to rely on msg.getMonotonicTimestamp().toUSec() instead of HRT.
* It stopped working when the time sync feature has been introduced, because it caused libuavcan
* to use an independent time source (based on hardware TIM5) instead of HRT.
* The proper solution is to be developed.
*/
_report.timestamp = hrt_absolute_time();
_report.x = (msg.magnetic_field_ga[0] - _scale.x_offset) * _scale.x_scale; _report.x = (msg.magnetic_field_ga[0] - _scale.x_offset) * _scale.x_scale;
_report.y = (msg.magnetic_field_ga[1] - _scale.y_offset) * _scale.y_scale; _report.y = (msg.magnetic_field_ga[1] - _scale.y_offset) * _scale.y_scale;

View File

@ -63,7 +63,7 @@ static inline void do_nothing(int level, ...)
#define PX4_ERR(...) ROS_WARN(__VA_ARGS__) #define PX4_ERR(...) ROS_WARN(__VA_ARGS__)
#define PX4_WARN(...) ROS_WARN(__VA_ARGS__) #define PX4_WARN(...) ROS_WARN(__VA_ARGS__)
#define PX4_INFO(...) ROS_WARN(__VA_ARGS__) #define PX4_INFO(...) ROS_WARN(__VA_ARGS__)
#define PX4_DEBUG(...) #define PX4_DEBUG(...)
#elif defined(__PX4_QURT) #elif defined(__PX4_QURT)
#include "qurt_log.h" #include "qurt_log.h"
@ -137,13 +137,13 @@ __END_DECLS
* *
* To write to a specific stream for each message type, open the streams and * To write to a specific stream for each message type, open the streams and
* set __px4__log_startline to something like: * set __px4__log_startline to something like:
* if (level <= __px4_log_level_current) printf(_px4_fd[level], * if (level <= __px4_log_level_current) printf(_px4_fd[level],
* *
* Additional behavior can be added using "{\" for __px4__log_startline and * Additional behavior can be added using "{\" for __px4__log_startline and
* "}" for __px4__log_endline and any other required setup or teardown steps * "}" for __px4__log_endline and any other required setup or teardown steps
****************************************************************************/ ****************************************************************************/
#define __px4__log_startcond(cond) if (cond) printf( #define __px4__log_printcond(cond, ...) if (cond) printf(__VA_ARGS__)
#define __px4__log_startline(level) if (level <= __px4_log_level_current) printf( #define __px4__log_printline(level, ...) if (level <= __px4_log_level_current) printf(__VA_ARGS__)
#define __px4__log_timestamp_fmt "%-10" PRIu64 " " #define __px4__log_timestamp_fmt "%-10" PRIu64 " "
#define __px4__log_timestamp_arg ,hrt_absolute_time() #define __px4__log_timestamp_arg ,hrt_absolute_time()
@ -172,12 +172,12 @@ __END_DECLS
* if the first arg/condition is true. * if the first arg/condition is true.
****************************************************************************/ ****************************************************************************/
#define __px4_log_named_cond(name, cond, FMT, ...) \ #define __px4_log_named_cond(name, cond, FMT, ...) \
__px4__log_startcond(cond)\ __px4__log_printcond(cond,\
"%s " \ "%s " \
FMT\ FMT\
__px4__log_end_fmt \ __px4__log_end_fmt \
,name, ##__VA_ARGS__\ ,name, ##__VA_ARGS__\
__px4__log_endline )
/**************************************************************************** /****************************************************************************
* __px4_log: * __px4_log:
@ -187,12 +187,12 @@ __END_DECLS
* printf("%-5s val is %d\n", __px4_log_level_str[3], val); * printf("%-5s val is %d\n", __px4_log_level_str[3], val);
****************************************************************************/ ****************************************************************************/
#define __px4_log(level, FMT, ...) \ #define __px4_log(level, FMT, ...) \
__px4__log_startline(level)\ __px4__log_printline(level,\
__px4__log_level_fmt \ __px4__log_level_fmt \
FMT\ FMT\
__px4__log_end_fmt \ __px4__log_end_fmt \
__px4__log_level_arg(level), ##__VA_ARGS__\ __px4__log_level_arg(level), ##__VA_ARGS__\
__px4__log_endline )
/**************************************************************************** /****************************************************************************
* __px4_log_timestamp: * __px4_log_timestamp:
@ -203,7 +203,7 @@ __END_DECLS
* hrt_absolute_time(), val); * hrt_absolute_time(), val);
****************************************************************************/ ****************************************************************************/
#define __px4_log_timestamp(level, FMT, ...) \ #define __px4_log_timestamp(level, FMT, ...) \
__px4__log_startline(level)\ __px4__log_printline(level,\
__px4__log_level_fmt\ __px4__log_level_fmt\
__px4__log_timestamp_fmt\ __px4__log_timestamp_fmt\
FMT\ FMT\
@ -211,7 +211,7 @@ __END_DECLS
__px4__log_level_arg(level)\ __px4__log_level_arg(level)\
__px4__log_timestamp_arg\ __px4__log_timestamp_arg\
, ##__VA_ARGS__\ , ##__VA_ARGS__\
__px4__log_endline )
/**************************************************************************** /****************************************************************************
* __px4_log_timestamp_thread: * __px4_log_timestamp_thread:
@ -222,7 +222,7 @@ __END_DECLS
* hrt_absolute_time(), pthread_self(), val); * hrt_absolute_time(), pthread_self(), val);
****************************************************************************/ ****************************************************************************/
#define __px4_log_timestamp_thread(level, FMT, ...) \ #define __px4_log_timestamp_thread(level, FMT, ...) \
__px4__log_startline(level)\ __px4__log_printline(level,\
__px4__log_level_fmt\ __px4__log_level_fmt\
__px4__log_timestamp_fmt\ __px4__log_timestamp_fmt\
__px4__log_thread_fmt\ __px4__log_thread_fmt\
@ -232,18 +232,18 @@ __END_DECLS
__px4__log_timestamp_arg\ __px4__log_timestamp_arg\
__px4__log_thread_arg\ __px4__log_thread_arg\
, ##__VA_ARGS__\ , ##__VA_ARGS__\
__px4__log_endline )
/**************************************************************************** /****************************************************************************
* __px4_log_file_and_line: * __px4_log_file_and_line:
* Convert a message in the form: * Convert a message in the form:
* PX4_WARN("val is %d", val); * PX4_WARN("val is %d", val);
* to * to
* printf("%-5s val is %d (file %s line %u)\n", * printf("%-5s val is %d (file %s line %u)\n",
* __px4_log_level_str[3], val, __FILE__, __LINE__); * __px4_log_level_str[3], val, __FILE__, __LINE__);
****************************************************************************/ ****************************************************************************/
#define __px4_log_file_and_line(level, FMT, ...) \ #define __px4_log_file_and_line(level, FMT, ...) \
__px4__log_startline(level)\ __px4__log_printline(level,\
__px4__log_level_fmt\ __px4__log_level_fmt\
__px4__log_timestamp_fmt\ __px4__log_timestamp_fmt\
FMT\ FMT\
@ -253,19 +253,19 @@ __END_DECLS
__px4__log_timestamp_arg\ __px4__log_timestamp_arg\
, ##__VA_ARGS__\ , ##__VA_ARGS__\
__px4__log_file_and_line_arg\ __px4__log_file_and_line_arg\
__px4__log_endline )
/**************************************************************************** /****************************************************************************
* __px4_log_timestamp_file_and_line: * __px4_log_timestamp_file_and_line:
* Convert a message in the form: * Convert a message in the form:
* PX4_WARN("val is %d", val); * PX4_WARN("val is %d", val);
* to * to
* printf("%-5s %-10lu val is %d (file %s line %u)\n", * printf("%-5s %-10lu val is %d (file %s line %u)\n",
* __px4_log_level_str[3], hrt_absolute_time(), * __px4_log_level_str[3], hrt_absolute_time(),
* val, __FILE__, __LINE__); * val, __FILE__, __LINE__);
****************************************************************************/ ****************************************************************************/
#define __px4_log_timestamp_file_and_line(level, FMT, ...) \ #define __px4_log_timestamp_file_and_line(level, FMT, ...) \
__px4__log_startline(level)\ __px4__log_printline(level,\
__px4__log_level_fmt\ __px4__log_level_fmt\
__px4__log_timestamp_fmt\ __px4__log_timestamp_fmt\
FMT\ FMT\
@ -275,19 +275,19 @@ __END_DECLS
__px4__log_timestamp_arg\ __px4__log_timestamp_arg\
, ##__VA_ARGS__\ , ##__VA_ARGS__\
__px4__log_file_and_line_arg\ __px4__log_file_and_line_arg\
__px4__log_endline )
/**************************************************************************** /****************************************************************************
* __px4_log_thread_file_and_line: * __px4_log_thread_file_and_line:
* Convert a message in the form: * Convert a message in the form:
* PX4_WARN("val is %d", val); * PX4_WARN("val is %d", val);
* to * to
* printf("%-5s %#X val is %d (file %s line %u)\n", * printf("%-5s %#X val is %d (file %s line %u)\n",
* __px4_log_level_str[3], pthread_self(), * __px4_log_level_str[3], pthread_self(),
* val, __FILE__, __LINE__); * val, __FILE__, __LINE__);
****************************************************************************/ ****************************************************************************/
#define __px4_log_thread_file_and_line(level, FMT, ...) \ #define __px4_log_thread_file_and_line(level, FMT, ...) \
__px4__log_startline(level)\ __px4__log_printline(level,\
__px4__log_level_fmt\ __px4__log_level_fmt\
__px4__log_thread_fmt\ __px4__log_thread_fmt\
FMT\ FMT\
@ -297,19 +297,19 @@ __END_DECLS
__px4__log_thread_arg\ __px4__log_thread_arg\
, ##__VA_ARGS__\ , ##__VA_ARGS__\
__px4__log_file_and_line_arg\ __px4__log_file_and_line_arg\
__px4__log_endline )
/**************************************************************************** /****************************************************************************
* __px4_log_timestamp_thread_file_and_line: * __px4_log_timestamp_thread_file_and_line:
* Convert a message in the form: * Convert a message in the form:
* PX4_WARN("val is %d", val); * PX4_WARN("val is %d", val);
* to * to
* printf("%-5s %-10lu %#X val is %d (file %s line %u)\n", * printf("%-5s %-10lu %#X val is %d (file %s line %u)\n",
* __px4_log_level_str[3], hrt_absolute_time(), * __px4_log_level_str[3], hrt_absolute_time(),
* pthread_self(), val, __FILE__, __LINE__); * pthread_self(), val, __FILE__, __LINE__);
****************************************************************************/ ****************************************************************************/
#define __px4_log_timestamp_thread_file_and_line(level, FMT, ...) \ #define __px4_log_timestamp_thread_file_and_line(level, FMT, ...) \
__px4__log_startline(level)\ __px4__log_printline(level,\
__px4__log_level_fmt\ __px4__log_level_fmt\
__px4__log_timestamp_fmt\ __px4__log_timestamp_fmt\
__px4__log_thread_fmt\ __px4__log_thread_fmt\
@ -321,7 +321,7 @@ __END_DECLS
__px4__log_thread_arg\ __px4__log_thread_arg\
, ##__VA_ARGS__\ , ##__VA_ARGS__\
__px4__log_file_and_line_arg\ __px4__log_file_and_line_arg\
__px4__log_endline )
/**************************************************************************** /****************************************************************************

View File

@ -233,7 +233,10 @@ esc_calib_main(int argc, char *argv[])
ret = poll(&fds, 1, 0); ret = poll(&fds, 1, 0);
if (ret > 0) { if (ret > 0) {
read(0, &c, 1); if (read(0, &c, 1) <= 0) {
printf("ESC calibration read error\n");
return 0;
}
if (c == 'y' || c == 'Y') { if (c == 'y' || c == 'Y') {
break; break;
@ -315,7 +318,10 @@ esc_calib_main(int argc, char *argv[])
ret = poll(&fds, 1, 0); ret = poll(&fds, 1, 0);
if (ret > 0) { if (ret > 0) {
read(0, &c, 1); if (read(0, &c, 1) <= 0) {
printf("ESC calibration read error\n");
goto done;
}
if (c == 13) { if (c == 13) {
break; break;
@ -352,7 +358,10 @@ esc_calib_main(int argc, char *argv[])
ret = poll(&fds, 1, 0); ret = poll(&fds, 1, 0);
if (ret > 0) { if (ret > 0) {
read(0, &c, 1); if (read(0, &c, 1) <= 0) {
printf("ESC calibration read error\n");
goto done;
}
if (c == 13) { if (c == 13) {
break; break;