diff --git a/posix-configs/bbblue/px4.config b/posix-configs/bbblue/px4.config index e72bb04883..99480f8612 100644 --- a/posix-configs/bbblue/px4.config +++ b/posix-configs/bbblue/px4.config @@ -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 diff --git a/posix-configs/bbblue/px4_fw.config b/posix-configs/bbblue/px4_fw.config index fd57a0d7f8..d235430ec1 100644 --- a/posix-configs/bbblue/px4_fw.config +++ b/posix-configs/bbblue/px4_fw.config @@ -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 diff --git a/src/drivers/boards/bbblue/init.c b/src/drivers/boards/bbblue/init.c index 354dfd9d01..eba6b7dc6b 100644 --- a/src/drivers/boards/bbblue/init.c +++ b/src/drivers/boards/bbblue/init.c @@ -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); diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index c0931e2cb5..a6df1a2eaa 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -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[]) _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[]) break; case 'n': - _mavlink_wifi_name = myoptarg; + _interface_name = myoptarg; break; #ifdef __PX4_POSIX diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index a85921a60c..09a54fdfae 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -63,10 +63,6 @@ #include #endif -#ifndef __DEFAULT_MAVLINK_WIFI -#define __DEFAULT_MAVLINK_WIFI "wlan" -#endif - #include #include #include @@ -606,7 +602,7 @@ private: unsigned _network_buf_len; #endif - const char *_mavlink_wifi_name; + const char *_interface_name; int _socket_fd; Protocol _protocol;