Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

mavlink: change mavlink output destination #6

Closed
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 6 additions & 0 deletions app/dashcam/src/main_flow/ArduPilot/dev_console.c
Original file line number Diff line number Diff line change
Expand Up @@ -966,6 +966,12 @@ static void check_wifi_txt(void)
if (strcmp(name, "CHANNEL") == 0) {
channel = atoi(value);
}

if (strcmp(name, "MAVLINK_DST_IP") == 0) {
mavlink_set_dst_ip(inet_addr(value));
} else if (strcmp(name, "MAVLINK_DST_PORT") == 0) {
mavlink_set_dst_port(atoi(value));
}
}

WiFi_QueryAndSet(SET_BEACON_OFF, NULL, NULL);
Expand Down
16 changes: 14 additions & 2 deletions app/dashcam/src/main_flow/ArduPilot/mavlink_wifi.c
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,8 @@ static int sitl_sock = -1;
static char stm32_id[40];
static bool rc_ok;
static bool vehicle_armed;
static uint32_t mavlink_dst_ip = INADDR_BROADCAST;
static uint16_t mavlink_dst_port = MAVLINK_DEST_PORT;

#define QUEUE_SIZE 50*1024

Expand Down Expand Up @@ -237,8 +239,8 @@ static void send_mavlink_wifi(int fd, mavlink_message_t *msg)
memset(&addr, 0x0, sizeof(addr));

addr.sin_family = AF_INET;
addr.sin_addr.s_addr = htonl(INADDR_BROADCAST);
addr.sin_port = htons(MAVLINK_DEST_PORT);
addr.sin_addr.s_addr = mavlink_dst_ip;
addr.sin_port = htons(mavlink_dst_port);

//console_printf("sending pkt of len %u\n", len);
sendto(fd, buf, len, 0, (struct sockaddr*)&addr, sizeof(addr));
Expand Down Expand Up @@ -1474,6 +1476,16 @@ void mavlink_set_sitl(bool enable)
console_printf("mavlink_sitl=%s\n", enable?"true":"false");
}

void mavlink_set_dst_ip(uint32_t ip)
{
mavlink_dst_ip = ip;
}

void mavlink_set_dst_port(uint16_t port)
{
mavlink_dst_port = port;
}

enum FlightCommand {
flightControllerTakeOff = 1,
flightControllerLand = 2,
Expand Down
2 changes: 2 additions & 0 deletions app/dashcam/src/main_flow/ArduPilot/mavlink_wifi.h
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,8 @@ void mavlink_show_stats(void);
void mavlink_set_debug(uint8_t debug_level);
int mavlink_set_flight_response(int index, int value);
void mavlink_set_sitl(bool enable);
void mavlink_set_dst_ip(uint32_t ip);
void mavlink_set_dst_port(uint16_t port);
int mavlink_fc_send(mavlink_message_t *msg);
bool toggle_recording(void);
bool take_snapshot(void);
Expand Down