Browse Source

Renamed mavlink wifi interface name and enabled land_detector

sbg
Bob-F 7 years ago committed by Beat Küng
parent
commit
a9bb274001
  1. 2
      posix-configs/bbblue/px4.config
  2. 2
      posix-configs/bbblue/px4_fw.config
  3. 2
      src/drivers/boards/bbblue/init.c
  4. 6
      src/modules/mavlink/mavlink_main.cpp
  5. 6
      src/modules/mavlink/mavlink_main.h

2
posix-configs/bbblue/px4.config

@ -64,7 +64,7 @@ sensors start @@ -64,7 +64,7 @@ sensors start
commander start
navigator start
ekf2 start
#land_detector start multicopter
land_detector start multicopter
mc_pos_control start
mc_att_control start

2
posix-configs/bbblue/px4_fw.config

@ -71,7 +71,7 @@ ekf2 start @@ -71,7 +71,7 @@ ekf2 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

2
src/drivers/boards/bbblue/init.c

@ -53,7 +53,7 @@ int rc_init(void) @@ -53,7 +53,7 @@ int rc_init(void)
if (rc_get_state() == RUNNING) { return 0; }
PX4_INFO("Initializing Robotics Cape library ...");
PX4_INFO("Initializing librobotcontrol ...");
// make sure another instance isn't running
rc_kill_existing_process(2.0f);

6
src/modules/mavlink/mavlink_main.cpp

@ -1150,7 +1150,7 @@ Mavlink::find_broadcast_address() @@ -1150,7 +1150,7 @@ 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);
if (strstr(cur_ifreq->ifr_name, _mavlink_wifi_name) == NULL) { continue; }
if (_interface_name && strstr(cur_ifreq->ifr_name, _interface_name) == NULL) { continue; }
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));
@ -1947,7 +1947,7 @@ Mavlink::task_main(int argc, char *argv[]) @@ -1947,7 +1947,7 @@ Mavlink::task_main(int argc, char *argv[])
_mode = MAVLINK_MODE_NORMAL;
bool _force_flow_control = false;
_mavlink_wifi_name = __DEFAULT_MAVLINK_WIFI;
_interface_name = nullptr;
#ifdef __PX4_NUTTX
/* the NuttX optarg handler does not
@ -1998,7 +1998,7 @@ Mavlink::task_main(int argc, char *argv[]) @@ -1998,7 +1998,7 @@ Mavlink::task_main(int argc, char *argv[])
break;
case 'n':
_mavlink_wifi_name = myoptarg;
_interface_name = myoptarg;
break;
#ifdef __PX4_POSIX

6
src/modules/mavlink/mavlink_main.h

@ -63,10 +63,6 @@ @@ -63,10 +63,6 @@
#include <net/if.h>
#endif
#ifndef __DEFAULT_MAVLINK_WIFI
#define __DEFAULT_MAVLINK_WIFI "wlan"
#endif
#include <uORB/uORB.h>
#include <uORB/topics/mission.h>
#include <uORB/topics/mission_result.h>
@ -606,7 +602,7 @@ private: @@ -606,7 +602,7 @@ private:
unsigned _network_buf_len;
#endif
const char *_mavlink_wifi_name;
const char *_interface_name;
int _socket_fd;
Protocol _protocol;

Loading…
Cancel
Save