UAVCAN IMU support in PX4

Does PX4/UAVCAN support using 9-dof IMU over the can bus. And more specifically, a 9-dof IMU that publishes absolute position rather than accel, gyro, mag. I think I know what the answer is but I don’t fully understand the code yet so thought id double check.

If I haven’t made sense above I’ll explain the setup a bit more, I have a CANnode capable of running i2c devices. I am using a BNO055 IMU (9-dof) with a custom driver that publishes the exact position to a uORB topic called sensor_attitude. I want to have this data sent through the canbus to be logged on my pixhawk.

If its not supported but is possible, some guidance of how to go about and where to start would be greatly appreciated.

Thanks

I have progressed this further and have my can node sending the data from the BNO, I am now having issues in receiving it on the pixhawk side. Does anyone have any guidance for writing the driver files for uavcan, eg - src/drivers/uavcan/sensors/accel.cpp and accel.hpp

the message can be seen publishing on the uavcan gui tool

edit: I can see it in uavcan gui but it thinks its empty and theres a constant spin error at the bottom thats constantly going. Perhaps not all is good on the node side? I have made my own dsdl file for this too

It would be nice to see your code, if you can share a GitHub link.
PX4 refers to an external device that publishes filtered position data (rather than raw sensor reading) as an INS.
So, if you’re sending position data, you’d want to write an INS driver.

Hi @dotanAtTrim , thanks for the reply

I think you may have misunderstood (or more likely I did not explain very well :upside_down_face:)

The driver itself for the IMU is already written and publishing in the uORB topic described above. The confusion has probably come from my use of the word “position”, I mean that it describes the exact orientation of the IMU, not the rates of the IMU unlike other IMU’s that PX4 supports.

My specific issue is the actual message being sent over the canbus, as I cant use the standard messages as they are setup for receiving accelerometer and gyro rates.

I’ve attempted to write the publishing file and subscribing files with little success. I cant share my GitHub repo for various reasons but I can copy in my code here

Subscription cpp and hpp

// guess at attitude.cpp

#include "attitude.hpp"
#include <drivers/drv_hrt.h>
#include <uORB/topics/sensor_attitude.h>

const char *const UavcanAttitudeBridge::NAME = "attitude";

UavcanAttitudeBridge::UavcanAttitudeBridge(uavcan::INode &node) :
	UavcanSensorBridgeBase("uavcan_attitude", ORB_ID(sensor_attitude)),
	_sub_bno_data(node)
{ }

int UavcanAttitudeBridge::init()
{
	int res = _sub_bno_data.start(BnoCbBinder(this, &UavcanAttitudeBridge::bno_sub_cb));

	if (res < 0) {
		DEVICE_LOG("failed to start uavcan sub: %d", res);
		return res;
	}

	return 0;
}


void UavcanAttitudeBridge::bno_sub_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::ahrs::Bno> &msg)
{
	auto report = ::sensor_attitude_s();

	report.timestamp = hrt_absolute_time();
	report.device_id = get_device_id();
	report.heading_deg = msg.heading;
	report.pitch_deg = msg.pitch;
	report.roll_deg = msg.roll;
	

	publish(msg.getSrcNodeID().get(), &report);
}

int UavcanAttitudeBridge::init_driver(uavcan_bridge::Channel *channel)
{
	return PX4_OK;
}

// guess at uavcan-sensors-hpp file for BNO055

#pragma once

#include "sensor_bridge.hpp"

#include <uavcan/equipment/ahrs/Bno.hpp>

class UavcanAttitudeBridge : public UavcanSensorBridgeBase
{

public:
	static const char *const NAME;

	UavcanAttitudeBridge(uavcan::INode &node);

	const char *get_name() const override { return NAME; }

	int init() override;


private:
	void bno_sub_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::ahrs::Bno> &msg);

	int init_driver(uavcan_bridge::Channel *channel) override;

	typedef uavcan::MethodBinder < UavcanAttitudeBridge *,
		void (UavcanAttitudeBridge::*)
		(const uavcan::ReceivedDataStructure<uavcan::equipment::ahrs::Bno> &) >
		BnoCbBinder;

	uavcan::Subscriber<uavcan::equipment::ahrs::Bno, BnoCbBinder> _sub_bno_data;
};

publisher

// attempt at uavcannode-publishers-Bno.hpp

#pragma once

#include "UavcanPublisherBase.hpp"

#include <uavcan/equipment/ahrs/Bno.hpp>

#include <uORB/SubscriptionCallback.hpp>
#include <uORB/topics/sensor_attitude.h>

namespace uavcannode
{

class Bno :
	public UavcanPublisherBase,
	public uORB::SubscriptionCallbackWorkItem,
	private uavcan::Publisher<uavcan::equipment::ahrs::Bno>
{
public:
	Bno(px4::WorkItem *work_item, uavcan::INode &node) :
		UavcanPublisherBase(uavcan::equipment::ahrs::Bno::DefaultDataTypeID),
		uORB::SubscriptionCallbackWorkItem(work_item, ORB_ID(sensor_attitude)),
		uavcan::Publisher<uavcan::equipment::ahrs::Bno>(node)
	{
		this->setPriority(uavcan::TransferPriority::MiddleLower);
	}

	void PrintInfo() override
	{
		if (uORB::SubscriptionCallbackWorkItem::advertised()) {
			printf("\t%s -> %s:%d\n",
			       uORB::SubscriptionCallbackWorkItem::get_topic()->o_name,
			       uavcan::equipment::ahrs::Bno::getDataTypeFullName(),
			       uavcan::equipment::ahrs::Bno::DefaultDataTypeID);
		}
	}

	void BroadcastAnyUpdates() override
	{
	
		sensor_attitude_s _sensor_att;

		if (uORB::SubscriptionCallbackWorkItem::update(&_sensor_att)) {

			if (!getNode().getUtcTime().isZero()) {
				uavcan::equipment::ahrs::Bno bno{};

				
				bno.timestamp.usec = getNode().getUtcTime().toUSec() - (hrt_absolute_time() - _sensor_att.timestamp);
				bno.
				//bno.(this part will come from uavcan/snesor/.cpp file, see gyro.cpp for more) = xxx(from bno055 driver)
				bno.heading = _sensor_att.heading_deg;
				bno.pitch = _sensor_att.pitch_deg;
				bno.roll = _sensor_att.roll_deg;


				uavcan::Publisher<uavcan::equipment::ahrs::Bno>::broadcast(bno);

			}

			uORB::SubscriptionCallbackWorkItem::registerCallback();
		}
	}
};
} // namespace uavcannode




Thanks
Owen

Sadly, I’m not familiar with UAVCAN, but if there’s a uORB topic that matches the data type you want to publish/subscribe to, I think it should work.

Looking back at the link I shared in my last comment - you want to publish AHRS data rather than IMU (rates) or INS (attitude and position).
I suggest looking at the vectornav (which is an INS) driver to see the uORB topics it uses, which aren’t sensor_attitude but bunch of other topics, and my point is you’d want to publish vehicle_attitude for example.
If I am not wrong -
You can either publish raw imu data (sensor data) or use whatever filter you want and publish attitude (vehicle attitude). That’s at the bare minimum.

If your only intention is to log the data, consider adding a custom uORB topic with the fields you want, that’s also an option.

Ahh right, I had another read and I think I see what you’re trying to get at now, unfortunately not all uORB topics will simply just “carry over” the can bus just because they exist in PX4

sensor_attitude is already my custom uORB topic and the IMU logs perfectly fine when running via I2C, but obviously I’m trying to move this to the can bus.

The ideal solution would be to have a driver that publishes raw data that can be sent over the can bus using the existing can drivers and then process the data post can bus but unfortunately I did not write the driver nor do I have the skill to figure any of it out!

I have figured it all out!!! I will write something here when i have time over the next week

Great. If there is something useful to add to the docs let me know and I can help.

@dakejahl FYI. in case you have something to add.

Definitely! Would a custom uavcan message section be good, a bit like we have for custom mavlink messages?

This is using the Ark CANnode - it runs PX4 - so at least for the publishing side it may be a more specific to just that device as its not necessarily applicable to all other can devices. The subscription side of things definitely could be helpful to all cases however!

Before I get started on putting some things together I was hoping to also to figure out custom messages for multi instance uORB topics, I can see its doable from the ESCStatus message but I cant quite figure it out, do you happen to know who might be able to help me out on this?

Can you open a pull request into GitHub - dronecan/DSDL: DSDL Protocol Description files for DroneCAN to add your new message? It would be best to get it upstreamed so that we don’t carry around custom messages. Regarding the DroneCAN to multi-uorb, checkout this PR which implements it for the ESC extended status message Add Support for DroneCAN Status Extended Message by vertiq-jordan · Pull Request #23896 · PX4/PX4-Autopilot · GitHub

will do -

Thanks for sending that PR that will be helpful when I get to the receiving side of things, but the step I’m actually struggling with is multi-uorb to DroneCAN rather than DroneCAN to multi-uorb. I’ve got multiple IMU’s on my CANnode, making multiple instances of a uorb topic, but can’t figure out how to get a DroneCAN message to send multiple sets of data. Specifically, writing the hpp file in the drivers/uavcannode/Publishers folder

Is there any example or explanations on this, or have I just misunderstood the PR?

Thanks

Ahh yeah I don’t think that’s been done before. It’s not supported currently. The Publisher classes use uORB::SubscriptionCallbackWorkItem which if you check the definition of the constructor, it defaults to the first uORB instance

	SubscriptionCallbackWorkItem(px4::WorkItem *work_item, const orb_metadata *meta, uint8_t instance = 0) :
		SubscriptionCallback(meta, 0, instance),	// interval 0
		_work_item(work_item)
	{
	}

I see, that does make sense. I’m interested to see how the ESCStatus.hpp message works then as the way that is setup is gives the impression it is sending multiple instances. This is found in the same place as my message.

void BroadcastAnyUpdates() override
	{
		// esc_status -> uavcan::equipment::esc::Status
		esc_status_s esc_status;

		if (uORB::SubscriptionCallbackWorkItem::update(&esc_status)) {

			for (size_t i = 0; i < esc_status.esc_count; i++) {
				uavcan::equipment::esc::Status status{};

				status.esc_index = i;
				status.error_count = esc_status.esc[i].esc_errorcount;
				status.voltage = esc_status.esc[i].esc_voltage;
				status.current = esc_status.esc[i].esc_current;
				status.temperature = esc_status.esc[i].esc_temperature;
				status.rpm = esc_status.esc[i].esc_rpm;
				//status.power_rating_pct = NAN;

				uavcan::Publisher<uavcan::equipment::esc::Status>::broadcast(status);

				// ensure callback is registered
				uORB::SubscriptionCallbackWorkItem::registerCallback();
			}
		}
	}

The EscStatus uORB message has an array of EscReport in it. So it’s a single uORB publisher. Your case is multiple uORB publishers to a single DroneCAN topic. You’re probably going to have to write some code to extend the implementation to support this.

1 Like

Oh okay that’s quite a neat trick actually, all I need to do now then is figure out how to iterate through the IMU’s before I publish the data. I didn’t write the driver for these IMU’s so I dont fully understand it all but ill figure it out