Skip to content

Commit

Permalink
Upgrade libcanard to 3.0 and rename uavcan_v1 to cyphal
Browse files Browse the repository at this point in the history
Did some prep work for redundant interfaces by introducing CanardHandle class to decouple physical interfaces from cyphal.cpp
  • Loading branch information
PetervdPerk-NXP authored and dagar committed May 10, 2022
1 parent 3ac8fdb commit b1ad4e8
Show file tree
Hide file tree
Showing 60 changed files with 967 additions and 802 deletions.
16 changes: 8 additions & 8 deletions .gitmodules
Original file line number Diff line number Diff line change
Expand Up @@ -36,14 +36,14 @@
[submodule "Tools/jsbsim_bridge"]
path = Tools/jsbsim_bridge
url = https://github.com/PX4/px4-jsbsim-bridge.git
[submodule "src/drivers/uavcan_v1/libcanard"]
path = src/drivers/uavcan_v1/libcanard
url = https://github.com/UAVCAN/libcanard.git
[submodule "src/drivers/uavcan_v1/public_regulated_data_types"]
path = src/drivers/uavcan_v1/public_regulated_data_types
url = https://github.com/UAVCAN/public_regulated_data_types.git
[submodule "src/drivers/uavcan_v1/legacy_data_types"]
path = src/drivers/uavcan_v1/legacy_data_types
[submodule "src/drivers/cyphal/libcanard"]
path = src/drivers/cyphal/libcanard
url = https://github.com/opencyphal/libcanard.git
[submodule "src/drivers/cyphal/public_regulated_data_types"]
path = src/drivers/cyphal/public_regulated_data_types
url = https://github.com/opencyphal/public_regulated_data_types.git
[submodule "src/drivers/cyphal/legacy_data_types"]
path = src/drivers/cyphal/legacy_data_types
url = https://github.com/PX4/public_regulated_data_types.git
branch = legacy
[submodule "src/lib/crypto/monocypher"]
Expand Down
4 changes: 2 additions & 2 deletions ROMFS/px4fmu_common/init.d/rcS
Original file line number Diff line number Diff line change
Expand Up @@ -298,9 +298,9 @@ else
tune_control play error
fi
else
if param greater -s UAVCAN_V1_ENABLE 0
if param greater -s CYPHAL_ENABLE 0
then
uavcan_v1 start
cyphal start
fi
fi

Expand Down
3 changes: 1 addition & 2 deletions Tools/astyle/files_to_check_code_style.sh
Original file line number Diff line number Diff line change
Expand Up @@ -13,8 +13,7 @@ exec find boards msg src platforms test \
-path platforms/qurt/dspal -prune -o \
-path src/drivers/uavcan/libuavcan -prune -o \
-path src/drivers/uavcan/uavcan_drivers/kinetis/driver/include/uavcan_kinetis -prune -o \
-path src/drivers/uavcan_v1/libcanard -prune -o \
-path src/drivers/uavcannode_gps_demo/libcanard -prune -o \
-path src/drivers/cyphal/libcanard -prune -o \
-path src/lib/crypto/monocypher -prune -o \
-path src/lib/events/libevents -prune -o \
-path src/lib/parameters/uthash -prune -o \
Expand Down
6 changes: 3 additions & 3 deletions boards/nxp/fmuk66-e/socketcan.px4board
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
CONFIG_DRIVERS_UAVCAN=n
CONFIG_DRIVERS_UAVCAN_V1=y
CONFIG_UAVCAN_V1_BMS_SUBSCRIBER=y
CONFIG_UAVCAN_V1_UORB_SENSOR_GPS_SUBSCRIBER=y
CONFIG_DRIVERS_CYPHAL=y
CONFIG_CYPHAL_BMS_SUBSCRIBER=y
CONFIG_CYPHAL_UORB_SENSOR_GPS_SUBSCRIBER=y
16 changes: 8 additions & 8 deletions boards/nxp/fmuk66-v3/socketcan.px4board
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
CONFIG_DRIVERS_UAVCAN=n
CONFIG_DRIVERS_UAVCAN_V1=y
CONFIG_UAVCAN_V1_BMS_SUBSCRIBER=y
CONFIG_UAVCAN_V1_ESC_SUBSCRIBER=y
CONFIG_UAVCAN_V1_GNSS_SUBSCRIBER_0=y
CONFIG_UAVCAN_V1_GNSS_SUBSCRIBER_1=y
CONFIG_UAVCAN_V1_READINESS_PUBLISHER=y
CONFIG_UAVCAN_V1_UORB_ACTUATOR_OUTPUTS_PUBLISHER=y
CONFIG_UAVCAN_V1_UORB_SENSOR_GPS_SUBSCRIBER=y
CONFIG_DRIVERS_CYPHAL=y
CONFIG_CYPHAL_BMS_SUBSCRIBER=y
CONFIG_CYPHAL_ESC_SUBSCRIBER=y
CONFIG_CYPHAL_GNSS_SUBSCRIBER_0=y
CONFIG_CYPHAL_GNSS_SUBSCRIBER_1=y
CONFIG_CYPHAL_READINESS_PUBLISHER=y
CONFIG_CYPHAL_UORB_ACTUATOR_OUTPUTS_PUBLISHER=y
CONFIG_CYPHAL_UORB_SENSOR_GPS_SUBSCRIBER=y
8 changes: 4 additions & 4 deletions boards/nxp/ucans32k146/default.px4board
Original file line number Diff line number Diff line change
Expand Up @@ -7,10 +7,10 @@ CONFIG_DRIVERS_BOOTLOADERS=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_LIGHTS_RGBLED_PWM=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_UAVCAN_V1=y
CONFIG_UAVCAN_V1_CLIENT=y
CONFIG_UAVCAN_V1_APP_DESCRIPTOR=y
CONFIG_UAVCAN_V1_UORB_SENSOR_GPS_PUBLISHER=y
CONFIG_DRIVERS_CYPHAL=y
CONFIG_CYPHAL_CLIENT=y
CONFIG_CYPHAL_APP_DESCRIPTOR=y
CONFIG_CYPHAL_UORB_SENSOR_GPS_PUBLISHER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_SYSTEMCMDS_I2CDETECT=y
CONFIG_SYSTEMCMDS_LED_CONTROL=y
Expand Down
2 changes: 1 addition & 1 deletion boards/nxp/ucans32k146/init/rc.board_defaults
Original file line number Diff line number Diff line change
Expand Up @@ -6,4 +6,4 @@
pwm_out mode_pwm1 start

ifup can0
uavcan_v1 start
cyphal start
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,6 @@
CONFIG_DRIVERS_HEATER=n
CONFIG_DRIVERS_OSD=n
CONFIG_DRIVERS_UAVCAN=n
CONFIG_DRIVERS_UAVCAN_V1=y
CONFIG_UAVCAN_V1_BMS_SUBSCRIBER=y
CONFIG_UAVCAN_V1_UORB_SENSOR_GPS_SUBSCRIBER=y
CONFIG_DRIVERS_CYPHAL=y
CONFIG_CYPHAL_BMS_SUBSCRIBER=y
CONFIG_CYPHAL_UORB_SENSOR_GPS_SUBSCRIBER=y
Original file line number Diff line number Diff line change
Expand Up @@ -34,13 +34,13 @@
/**
* @file EscClient.hpp
*
* Client-side implementation of DS-15 specification ESC service
* Client-side implementation of UDRAL specification ESC service
*
* Publishes the following UAVCAN v1 messages:
* Publishes the following Cyphal messages:
* reg.drone.service.actuator.common.sp.Value8.0.1
* reg.drone.service.common.Readiness.0.1
*
* Subscribes to the following UAVCAN v1 messages:
* Subscribes to the following Cyphal messages:
* reg.drone.service.actuator.common.Feedback.0.1
* reg.drone.service.actuator.common.Status.0.1
*
Expand All @@ -57,18 +57,18 @@
#include <drivers/drv_hrt.h>
#include <lib/mixer_module/mixer_module.hpp>

// DS-15 Specification Messages
#include <reg/drone/service/actuator/common/sp/Vector31_0_1.h>
#include <reg/drone/service/common/Readiness_0_1.h>
// UDRAL Specification Messages
#include <reg/udral/service/actuator/common/sp/Vector31_0_1.h>
#include <reg/udral/service/common/Readiness_0_1.h>

/// TODO: Allow derived class of Subscription at same time, to handle ESC Feedback/Status
class UavcanEscController : public UavcanPublisher
{
public:
static constexpr int MAX_ACTUATORS = MixingOutput::MAX_ACTUATORS;

UavcanEscController(CanardInstance &ins, UavcanParamManager &pmgr) :
UavcanPublisher(ins, pmgr, "ds_015", "esc") { };
UavcanEscController(CanardHandle &handle, UavcanParamManager &pmgr) :
UavcanPublisher(handle, pmgr, "udral", "esc") { };

~UavcanEscController() {};

Expand All @@ -80,45 +80,47 @@ class UavcanEscController : public UavcanPublisher

if (new_arming.armed != _armed.armed) {
_armed = new_arming;
size_t payload_size = reg_udral_service_common_Readiness_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_;

// Only publish if we have a valid publication ID set
if (_port_id == 0) {
return;
}

reg_drone_service_common_Readiness_0_1 msg_arming {};
reg_udral_service_common_Readiness_0_1 msg_arming {};

if (_armed.armed) {
msg_arming.value = reg_drone_service_common_Readiness_0_1_ENGAGED;
msg_arming.value = reg_udral_service_common_Readiness_0_1_ENGAGED;

} else if (_armed.prearmed) {
msg_arming.value = reg_drone_service_common_Readiness_0_1_STANDBY;
msg_arming.value = reg_udral_service_common_Readiness_0_1_STANDBY;

} else {
msg_arming.value = reg_drone_service_common_Readiness_0_1_SLEEP;
msg_arming.value = reg_udral_service_common_Readiness_0_1_SLEEP;
}

uint8_t arming_payload_buffer[reg_drone_service_common_Readiness_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_];
uint8_t arming_payload_buffer[reg_udral_service_common_Readiness_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_];

CanardPortID arming_pid = static_cast<CanardPortID>(static_cast<uint32_t>(_port_id) + 1);
CanardTransfer transfer = {
.timestamp_usec = hrt_absolute_time() + PUBLISHER_DEFAULT_TIMEOUT_USEC,
const CanardTransferMetadata transfer_metadata = {
.priority = CanardPriorityNominal,
.transfer_kind = CanardTransferKindMessage,
.port_id = arming_pid, // This is the subject-ID.
.remote_node_id = CANARD_NODE_ID_UNSET, // Messages cannot be unicast, so use UNSET.
.transfer_id = _arming_transfer_id,
.payload_size = reg_drone_service_common_Readiness_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_,
.payload = &arming_payload_buffer,
};

int result = reg_drone_service_common_Readiness_0_1_serialize_(&msg_arming, arming_payload_buffer,
&transfer.payload_size);
int result = reg_udral_service_common_Readiness_0_1_serialize_(&msg_arming, arming_payload_buffer,
&payload_size);

if (result == 0) {
// set the data ready in the buffer and chop if needed
++_arming_transfer_id; // The transfer-ID shall be incremented after every transmission on this subject.
result = canardTxPush(&_canard_instance, &transfer);
result = _canard_handle.TxPush(hrt_absolute_time() + PUBLISHER_DEFAULT_TIMEOUT_USEC,
&transfer_metadata,
payload_size,
&arming_payload_buffer
);
}
}
}
Expand All @@ -127,7 +129,8 @@ class UavcanEscController : public UavcanPublisher
void update_outputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS], unsigned num_outputs)
{
if (_port_id > 0) {
reg_drone_service_actuator_common_sp_Vector31_0_1 msg_sp {0};
reg_udral_service_actuator_common_sp_Vector31_0_1 msg_sp {0};
size_t payload_size = reg_udral_service_common_Readiness_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_;

for (uint8_t i = 0; i < MAX_ACTUATORS; i++) {
if (i < num_outputs) {
Expand All @@ -139,29 +142,30 @@ class UavcanEscController : public UavcanPublisher
}
}


PX4_INFO("Publish %d values %f, %f, %f, %f", num_outputs, (double)msg_sp.value[0], (double)msg_sp.value[1],
(double)msg_sp.value[2], (double)msg_sp.value[3]);

uint8_t esc_sp_payload_buffer[reg_drone_service_actuator_common_sp_Vector31_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_];
uint8_t esc_sp_payload_buffer[reg_udral_service_actuator_common_sp_Vector31_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_];

CanardTransfer transfer = {
.timestamp_usec = hrt_absolute_time() + PUBLISHER_DEFAULT_TIMEOUT_USEC,
const CanardTransferMetadata transfer_metadata = {
.priority = CanardPriorityNominal,
.transfer_kind = CanardTransferKindMessage,
.port_id = _port_id, // This is the subject-ID.
.remote_node_id = CANARD_NODE_ID_UNSET, // Messages cannot be unicast, so use UNSET.
.transfer_id = _transfer_id,
.payload_size = reg_drone_service_actuator_common_sp_Vector31_0_1_SERIALIZATION_BUFFER_SIZE_BYTES_,
.payload = &esc_sp_payload_buffer,
};

int result = reg_drone_service_actuator_common_sp_Vector31_0_1_serialize_(&msg_sp, esc_sp_payload_buffer,
&transfer.payload_size);
int result = reg_udral_service_actuator_common_sp_Vector31_0_1_serialize_(&msg_sp, esc_sp_payload_buffer,
&payload_size);

if (result == 0) {
// set the data ready in the buffer and chop if needed
++_transfer_id; // The transfer-ID shall be incremented after every transmission on this subject.
result = canardTxPush(&_canard_instance, &transfer);
result = _canard_handle.TxPush(hrt_absolute_time() + PUBLISHER_DEFAULT_TIMEOUT_USEC,
&transfer_metadata,
payload_size,
&esc_sp_payload_buffer);
}
}
};
Expand All @@ -175,7 +179,7 @@ class UavcanEscController : public UavcanPublisher
/**
* ESC status message reception will be reported via this callback.
*/
void esc_status_sub_cb(const CanardTransfer &msg);
void esc_status_sub_cb(const CanardRxTransfer &msg);

uint8_t _rotor_count {0};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,14 +34,14 @@
/**
* @file EscServer.hpp
*
* Server-side implementation of DS-15 specification ESC service
* Server-side implementation of UDRAL specification ESC service
* (Used for CANNode control of an ESC via PWM output)
*
* Subscribes to the following UAVCAN v1 messages:
* Subscribes to the following Cyphal messages:
* reg.drone.service.actuator.common.sp.Value8.0.1
* reg.drone.service.common.Readiness.0.1
*
* Publishes to the following UAVCAN v1 messages:
* Publishes to the following Cyphal messages:
* reg.drone.service.actuator.common.Feedback.0.1
* reg.drone.service.actuator.common.Status.0.1
*
Expand All @@ -62,7 +62,7 @@
#include <drivers/drv_hrt.h>
#include <lib/mixer_module/mixer_module.hpp>

// DS-15 Specification Messages
// UDRAL Specification Messages
#include <reg/drone/service/actuator/common/sp/Vector31_0_1.h>
#include <reg/drone/service/common/Readiness_0_1.h>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ px4_add_git_submodule(TARGET git_legacy_data_types PATH ${LEGACY_DSDL_DIR})

find_program(NNVG_PATH nnvg)
if(NNVG_PATH)
message("Generating UAVCANv1 DSDL headers using Nunavut")
message("Generating Cyphal DSDL headers using Nunavut")
execute_process(COMMAND ${NNVG_PATH} --outdir ${CMAKE_CURRENT_BINARY_DIR}/dsdlc_generated --target-language c -I ${DSDL_DIR}/uavcan ${DSDL_DIR}/reg)
execute_process(COMMAND ${NNVG_PATH} --outdir ${CMAKE_CURRENT_BINARY_DIR}/dsdlc_generated --target-language c -I ${LEGACY_DSDL_DIR}/uavcan ${LEGACY_DSDL_DIR}/legacy)
execute_process(COMMAND ${NNVG_PATH} --outdir ${CMAKE_CURRENT_BINARY_DIR}/dsdlc_generated --target-language c ${DSDL_DIR}/uavcan)
Expand All @@ -66,14 +66,14 @@ if(${PX4_PLATFORM} MATCHES "nuttx")
endif()
endif()

if(CONFIG_UAVCAN_V1_NODE_MANAGER)
if(CONFIG_CYPHAL_NODE_MANAGER)
list(APPEND SRCS
NodeManager.hpp
NodeManager.cpp
)
endif()

if(CONFIG_UAVCAN_V1_NODE_CLIENT)
if(CONFIG_CYPHAL_NODE_CLIENT)
list(APPEND SRCS
NodeClient.hpp
NodeClient.cpp
Expand All @@ -86,29 +86,31 @@ endif()
# Temporary measure to get Kconfig option as defines into this application
# Ideally we want nicely decouple and define this in kconfig.cmake
# But then we need to overhaul the src modules naming convention
set(DRIVERS_UAVCAN_V1_OPTIONS)
set(DRIVERS_CYPHAL_OPTIONS)
get_cmake_property(_variableNames VARIABLES)
foreach (_variableName ${_variableNames})
string(REGEX MATCH "^CONFIG_UAVCAN_V1_" UAVCAN_V1_OPTION ${_variableName})
string(REGEX MATCH "^CONFIG_CYPHAL_" CYPHAL_OPTION ${_variableName})

if(UAVCAN_V1_OPTION)
if(CYPHAL_OPTION)
if(${${_variableName}} STREQUAL "y")
list(APPEND DRIVERS_UAVCAN_V1_OPTIONS "-D${_variableName}=1")
list(APPEND DRIVERS_CYPHAL_OPTIONS "-D${_variableName}=1")
else()
list(APPEND DRIVERS_UAVCAN_V1_OPTIONS "-D${_variableName}=${${_variableName}}")
list(APPEND DRIVERS_CYPHAL_OPTIONS "-D${_variableName}=${${_variableName}}")
endif()
endif()
endforeach()

remove_definitions(-Werror)

px4_add_module(
MODULE drivers__uavcan_v1
MAIN uavcan_v1
MODULE drivers__cyphal
MAIN cyphal
STACK_MAIN 4096
COMPILE_FLAGS
#-DCANARD_ASSERT
-DUINT32_C\(x\)=__UINT32_C\(x\)
-O0
${DRIVERS_UAVCAN_V1_OPTIONS}
${DRIVERS_CYPHAL_OPTIONS}
INCLUDES
${LIBCANARD_DIR}/libcanard/
${CMAKE_CURRENT_BINARY_DIR}/dsdlc_generated
Expand All @@ -119,8 +121,9 @@ px4_add_module(
SubscriptionManager.hpp
ParamManager.hpp
ParamManager.cpp
Uavcan.cpp
Uavcan.hpp
Cyphal.cpp
Cyphal.hpp
CanardHandle.cpp
Publishers/uORB/uorb_publisher.cpp
Subscribers/uORB/uorb_subscriber.cpp
${SRCS}
Expand All @@ -137,3 +140,6 @@ px4_add_module(
version
${DPNDS}
)

# libcanard 3.0 introduces this warning, for now no intention to fix it thus we ignore this warning
set_source_files_properties(${LIBCANARD_DIR}/libcanard/canard.c PROPERTIES COMPILE_FLAGS -Wno-cast-align)
Loading

0 comments on commit b1ad4e8

Please sign in to comment.