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

RTPS test branch #9224

Merged
merged 2 commits into from
May 23, 2018
Merged
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
4 changes: 4 additions & 0 deletions ROMFS/px4fmu_common/init.d/rcS
Original file line number Diff line number Diff line change
Expand Up @@ -670,6 +670,10 @@ then
then
mavlink start -d ${MAVLINK_COMPANION_DEVICE} -b 115200 -m minimal -r 1000
fi
if param compare SYS_COMPANION 6460800
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Any reason to establish the RTPS client to half the baud rate of the ESP8266?

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I was following another example at the time using this baudrate. Feel free to change it to a more appropriate default, or add a range of desired rates.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I see. @avinash-palleti do you see any problem on keeping the baudrate at the max possible?

then
micrortps_client start -t UART -d /dev/ttyS2 -b 460800
fi
if param compare SYS_COMPANION 1921600
then
mavlink start -d ${MAVLINK_COMPANION_DEVICE} -b 921600 -r 20000
Expand Down
9 changes: 8 additions & 1 deletion src/modules/micrortps_bridge/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,13 @@ if(NOT FASTRTPSGEN)
endif()

set(config_rtps_send_topics
sensor_combined
sensor_combined
sensor_baro
sensor_selection
vehicle_gps_position
airspeed
vehicle_land_detected
vehicle_status
)

set(config_rtps_receive_topics
Expand Down Expand Up @@ -71,6 +77,7 @@ if (GENERATE_RTPS_BRIDGE)
set(uorb_sources_microcdr)

# send topic files
message(STATUS "RTPS send: ${config_rtps_send_topics}")
set(send_topic_files)
foreach(topic ${config_rtps_send_topics})
list(APPEND send_topic_files ${PX4_SOURCE_DIR}/msg/${topic}.msg)
Expand Down
1 change: 1 addition & 0 deletions src/modules/systemlib/system_params.c
Original file line number Diff line number Diff line change
Expand Up @@ -130,6 +130,7 @@ PARAM_DEFINE_INT32(SYS_MC_EST_GROUP, 2);
* @value 538400 Minimal Telemetry (38400 baud, 8N1)
* @value 557600 Minimal Telemetry (57600 baud, 8N1)
* @value 5115200 Minimal Telemetry (115200 baud, 8N1)
* @value 6460800 RTPS Client (460800 baud)
* @value 1921600 ESP8266 (921600 baud, 8N1)
*
* @min 0
Expand Down