Browse Source

update according to pull request review comments

sbg
Bob-F 7 years ago committed by Beat Küng
parent
commit
627ea3b23e
  1. 15
      platforms/posix/cmake/px4_impl_os.cmake
  2. 4
      posix-configs/bbblue/px4.config
  3. 4
      src/drivers/linux_pwm_out/bbblue_pwm_rc.cpp
  4. 3
      src/drivers/linux_sbus/linux_sbus.cpp
  5. 10
      src/modules/mavlink/mavlink_main.cpp
  6. 8
      src/modules/mavlink/mavlink_main.h
  7. 2
      src/modules/sensors/sensor_params_battery.c
  8. 1
      src/modules/sensors/voted_sensors_update.cpp

15
platforms/posix/cmake/px4_impl_os.cmake

@ -289,14 +289,19 @@ function(px4_os_add_flags) @@ -289,14 +289,19 @@ function(px4_os_add_flags)
list(APPEND added_c_flags ${BBBLUE_COMPILE_FLAGS})
list(APPEND added_cxx_flags ${BBBLUE_COMPILE_FLAGS})
set(LIBROBOTCONTROL_INSTALL_DIR $ENV{LIBROBOTCONTROL_INSTALL_DIR})
# TODO: Wmissing-field-initializers ignored on older toolchain, can be removed eventually
#
# On cross compile host system and native build system:
# a) install robotcontrol.h and rc/* into /usr/local/include
# b) install pre-built native (ARM) version of librobotcontrol.* into /usr/local/lib
list(APPEND added_cxx_flags -I/usr/local/include -Wno-missing-field-initializers)
list(APPEND added_c_flags -I/usr/local/include)
# a) select and define LIBROBOTCONTROL_INSTALL_DIR environment variable so that
# other unwanted headers will not be included
# b) install robotcontrol.h and rc/* into $LIBROBOTCONTROL_INSTALL_DIR/include
# c) install pre-built native (ARM) version of librobotcontrol.* into $LIBROBOTCONTROL_INSTALL_DIR/lib
list(APPEND added_cxx_flags -I${LIBROBOTCONTROL_INSTALL_DIR}/include -Wno-missing-field-initializers)
list(APPEND added_c_flags -I${LIBROBOTCONTROL_INSTALL_DIR}/include)
list(APPEND added_exe_linker_flags -L/usr/local/lib)
list(APPEND added_exe_linker_flags -L${LIBROBOTCONTROL_INSTALL_DIR}/lib)
endif()
# output

4
posix-configs/bbblue/px4.config

@ -71,9 +71,9 @@ mc_att_control start @@ -71,9 +71,9 @@ mc_att_control start
#fw_att_control start
#fw_pos_control_l1 start
mavlink start -x -u 14556 -r 1000000
mavlink start -n SoftAp -x -u 14556 -r 1000000
# -n name of wifi interface: SoftAp, wlan or your custom interface,
# e.g., -n wlan . The default on BBBlue is SoftAp
# e.g., -n SoftAp . The default is wlan
sleep 1

4
src/drivers/linux_pwm_out/bbblue_pwm_rc.cpp

@ -30,7 +30,7 @@ @@ -30,7 +30,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#ifdef __DF_BBBLUE
#ifdef __PX4_POSIX_BBBLUE
#include <fcntl.h>
#include <errno.h>
@ -79,4 +79,4 @@ int BBBlueRcPWMOut::send_output_pwm(const uint16_t *pwm, int num_outputs) @@ -79,4 +79,4 @@ int BBBlueRcPWMOut::send_output_pwm(const uint16_t *pwm, int num_outputs)
return ret;
}
#endif // __DF_BBBLUE
#endif // __PX4_POSIX_BBBLUE

3
src/drivers/linux_sbus/linux_sbus.cpp

@ -42,8 +42,7 @@ int RcInput::init() @@ -42,8 +42,7 @@ int RcInput::init()
/**
* initialize the data of each channel
*/
for (i = 0; i < input_rc_s::RC_INPUT_MAX_CHANNELS && i < 16; ++i) {
//_data.values defined as int[16] and RC_INPUT_MAX_CHANNELS (=18) > 16
for (i = 0; i < input_rc_s::RC_INPUT_MAX_CHANNELS; ++i) {
_data.values[i] = UINT16_MAX;
}

10
src/modules/mavlink/mavlink_main.cpp

@ -1150,12 +1150,8 @@ Mavlink::find_broadcast_address() @@ -1150,12 +1150,8 @@ Mavlink::find_broadcast_address()
const struct in_addr netmask_addr = query_netmask_addr(_socket_fd, *cur_ifreq);
const struct in_addr broadcast_addr = compute_broadcast_addr(sin_addr, netmask_addr);
#ifdef __PX4_POSIX_BBBLUE
if (strstr(cur_ifreq->ifr_name, _mavlink_wifi_name) == NULL) { continue; }
#endif
PX4_INFO("using network interface %s, IP: %s", cur_ifreq->ifr_name, inet_ntoa(sin_addr));
PX4_INFO("with netmask: %s", inet_ntoa(netmask_addr));
PX4_INFO("and broadcast IP: %s", inet_ntoa(broadcast_addr));
@ -1951,9 +1947,7 @@ Mavlink::task_main(int argc, char *argv[]) @@ -1951,9 +1947,7 @@ Mavlink::task_main(int argc, char *argv[])
_mode = MAVLINK_MODE_NORMAL;
bool _force_flow_control = false;
#ifdef __PX4_POSIX_BBBLUE
_mavlink_wifi_name = __PX4_BBBLUE_DEFAULT_MAVLINK_WIFI;
#endif
_mavlink_wifi_name = __DEFAULT_MAVLINK_WIFI;
#ifdef __PX4_NUTTX
/* the NuttX optarg handler does not
@ -2004,9 +1998,7 @@ Mavlink::task_main(int argc, char *argv[]) @@ -2004,9 +1998,7 @@ Mavlink::task_main(int argc, char *argv[])
break;
case 'n':
#ifdef __PX4_POSIX_BBBLUE
_mavlink_wifi_name = myoptarg;
#endif
break;
#ifdef __PX4_POSIX

8
src/modules/mavlink/mavlink_main.h

@ -63,10 +63,8 @@ @@ -63,10 +63,8 @@
#include <net/if.h>
#endif
#ifdef __PX4_POSIX_BBBLUE
#ifndef __PX4_BBBLUE_DEFAULT_MAVLINK_WIFI
#define __PX4_BBBLUE_DEFAULT_MAVLINK_WIFI "SoftAp"
#endif
#ifndef __DEFAULT_MAVLINK_WIFI
#define __DEFAULT_MAVLINK_WIFI "wlan"
#endif
#include <uORB/uORB.h>
@ -608,9 +606,7 @@ private: @@ -608,9 +606,7 @@ private:
unsigned _network_buf_len;
#endif
#ifdef __PX4_POSIX_BBBLUE
const char *_mavlink_wifi_name;
#endif
int _socket_fd;
Protocol _protocol;

2
src/modules/sensors/sensor_params_battery.c

@ -98,7 +98,7 @@ PARAM_DEFINE_FLOAT(BAT_A_PER_V, -1.0); @@ -98,7 +98,7 @@ PARAM_DEFINE_FLOAT(BAT_A_PER_V, -1.0);
* means that measurements are expected to come from a power module. If the value is set to
* 'External' then the system expects to receive mavlink battery status messages.
*
* @min -1
* @min 0
* @max 1
* @value 0 Power Module
* @value 1 External

1
src/modules/sensors/voted_sensors_update.cpp

@ -626,7 +626,6 @@ void VotedSensorsUpdate::accel_poll(struct sensor_combined_s &raw) @@ -626,7 +626,6 @@ void VotedSensorsUpdate::accel_poll(struct sensor_combined_s &raw)
// write the best sensor data to the output variables
if (best_index >= 0) {
raw.timestamp = _last_sensor_data[best_index].timestamp;
raw.accelerometer_integral_dt = _last_sensor_data[best_index].accelerometer_integral_dt;
memcpy(&raw.accelerometer_m_s2, &_last_sensor_data[best_index].accelerometer_m_s2, sizeof(raw.accelerometer_m_s2));

Loading…
Cancel
Save