在PX4中添加自己的can驱动

想在px4开源无人机中源码里面添加自己的can设备,于是我仿照uavcan中的beep.hpp写了一份自己的源码。
这是beep中结构



#pragma once

#include <uavcan/uavcan.hpp>
#include <uavcan/equipment/indication/BeepCommand.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/tune_control.h>
#include <lib/tunes/tunes.h>

class UavcanBeepController
{
public:
	UavcanBeepController(uavcan::INode &node);

	/*
	* setup periodic updater
	*/
	int init();

private:
	/*
	 * Max update rate to avoid excessive bus traffic
	 */
	static constexpr unsigned MAX_RATE_HZ = 100;

	/*
	 * Setup timer and call back function for periodic updates
	 */
	void periodic_update(const uavcan::TimerEvent &);

	typedef uavcan::MethodBinder<UavcanBeepController *, void (UavcanBeepController::*)(const uavcan::TimerEvent &)>
	TimerCbBinder;

	/*
	 * Subscription tune_control
	 */
	uORB::Subscription _tune_control_sub{ORB_ID(tune_control)};

	/*
	 * Publish CAN Beep
	 */
	uavcan::Publisher<uavcan::equipment::indication::BeepCommand> _beep_pub;

	uavcan::TimerEventForwarder<TimerCbBinder> _timer;

	hrt_abstime _interval_timestamp{0};
	tune_control_s _tune{};
	Tunes _tunes{};
	unsigned int _silence_length{0};	///< If nonzero, silence before next note.
	unsigned int _frequency{0};
	unsigned int _duration{0};
};

下面是我自己写的代码结构

/****************************************************************************
*
*   Copyright (c) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
*    notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
*    notice, this list of conditions and the following disclaimer in
*    the documentation and/or other materials provided with the
*    distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
*    used to endorse or promote products derived from this software
*    without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/

/**
 * @file car_wheel.hpp
 *
 * @author liuda
 * @brief Control CAN wheel
 *
 */

#pragma once

#include <uavcan/uavcan.hpp>
#include <uavcan/equipment/indication/BeepCommand.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/tune_control.h>
#include <lib/tunes/tunes.h>

class UavcanWheelController
{
public:
	UavcanWheelController(uavcan::INode &node);

	/*
	* setup periodic updater
	*/
	int init();

private:
	/*
	 * Max update rate to avoid excessive bus traffic
	 */


	/*
	 * Setup timer and call back function for periodic update
	 * Subscription tune_control
	 */


	/*
	 * Publish CAN Beep
	 */
	uavcan::INode node1;
         uavcan::MonotonicTime tx_deadline;  // 截止时间为当前时间加上100毫秒
	uint32_t can_id=0x0200;  // 扩展帧
	// uint8_t can_data[8];
	uint8_t data_len = 8;
	//uavcan::CanFrame frame;
	uint8_t iface_mask = 3;  // 将帧发送到接口0和接口1
	uavcan::CanTxQueue::Qos qos = uavcan::CanTxQueue::Volatile;
	uavcan::CanIOFlags flags = 1;
};

我在beep对应的camkelis中加入自己的代码,其中carwheel是我的代码

px4_add_module(
	MODULE drivers__uavcan
	MAIN uavcan
	STACK_MAIN 4096
	COMPILE_FLAGS
		-Wno-format-security # logmessage.hpp
		#-O0
		#-DDEBUG_BUILD
	INCLUDES
		${DSDLC_OUTPUT}
		${LIBUAVCAN_DIR}/libuavcan/include
		${LIBUAVCAN_DIR}/libuavcan/include/dsdlc_generated
		${LIBUAVCAN_DIR}/libuavcan_drivers/posix/include
		${LIBUAVCAN_DIR_DRIVERS}/${UAVCAN_DRIVER}/driver/include
	SRCS
		arming_status.cpp
		arming_status.hpp
		beep.cpp
		beep.hpp
		car_wheel.cpp
		car_wheel.hpp
		remoteid.cpp
		remoteid.hpp
		rgbled.cpp
		rgbled.hpp
		safety_state.cpp
		safety_state.hpp

		# Main
		uavcan_main.cpp
		uavcan_servers.cpp

		# Actuators
		actuators/esc.cpp
		actuators/hardpoint.cpp
		actuators/servo.cpp

		# Sensors
		sensors/sensor_bridge.cpp
		sensors/differential_pressure.cpp
		sensors/baro.cpp
		sensors/battery.cpp
		sensors/airspeed.cpp
		sensors/flow.cpp
		sensors/fuel_tank_status.cpp
		sensors/gnss_relative.cpp
		sensors/gnss.cpp
		sensors/mag.cpp
		sensors/rangefinder.cpp
		sensors/accel.cpp
		sensors/gyro.cpp
		sensors/ice_status.cpp
		sensors/hygrometer.cpp
		sensors/safety_button.cpp
	MODULE_CONFIG
		module.yaml
	DEPENDS
		px4_uavcan_dsdlc

		button_publisher
		drivers_rangefinder
		led
		mixer_module
		version

		git_uavcan
		uavcan_${UAVCAN_DRIVER}_driver

		drivers_rangefinder # Fix undefined reference when no distance sensors are selected

		# within libuavcan
		uavcan

加入后可以成功编译。
所以我继续把我的代码加入到uavcan_main.cpp中运行起来.
首先将实例化加入到 uavcan的hpp里面

	pthread_mutex_t			_node_mutex;

#if defined(CONFIG_UAVCAN_ARMING_CONTROLLER)
	UavcanArmingStatus		_arming_status_controller;
#endif
#if defined(CONFIG_UAVCAN_BEEP_CONTROLLER)
	UavcanBeepController		_beep_controller;
#endif
#if defined(CONFIG_UAVCAN_OUTPUTS_CONTROLLER)
	UavcanEscController		_esc_controller;
	UavcanMixingInterfaceESC 	_mixing_interface_esc{_node_mutex, _esc_controller};

	UavcanServoController		_servo_controller;
	UavcanMixingInterfaceServo 	_mixing_interface_servo{_node_mutex, _servo_controller};
#endif
#if defined(CONFIG_UAVCAN_HARDPOINT_CONTROLLER)
	UavcanHardpointController	_hardpoint_controller;
#endif
#if defined(CONFIG_UAVCAN_SAFETY_STATE_CONTROLLER)
	UavcanSafetyState         	_safety_state_controller;
#endif
#if defined(CONFIG_UAVCAN_REMOTEID_CONTROLLER)
	UavcanRemoteIDController _remoteid_controller;
#endif
#if defined(CONFIG_UAVCAN_RGB_CONTROLLER)
	UavcanRGBController             _rgbled_controller;
#endif
	UavcanWheelController		_wheel_ctrl;

然后在uavcan_main.cpp中初始化列表


#include <px4_platform_common/px4_config.h>
#include <px4_platform_common/tasks.h>

#include <inttypes.h>
#include <cstdlib>
#include <cstring>
#include <fcntl.h>
#include <systemlib/err.h>
#include <parameters/param.h>
#include <version/version.h>

#include <arch/chip/chip.h>

#include <uORB/topics/esc_status.h>

#include <drivers/drv_hrt.h>

#include "uavcan_module.hpp"
#include "uavcan_main.hpp"
#include <uavcan/util/templates.hpp>

#include <uavcan/protocol/param/ExecuteOpcode.hpp>

//todo:The Inclusion of file_server_backend is killing
// #include <sys/types.h> and leaving OK undefined
# define OK 0

/*
 * UavcanNode
 */
UavcanNode *UavcanNode::_instance;

static UavcanNode::CanInitHelper *can = nullptr;

UavcanNode::UavcanNode(uavcan::ICanDriver &can_driver, uavcan::ISystemClock &system_clock) :
	ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::uavcan),
	ModuleParams(nullptr),
	_node(can_driver, system_clock, _pool_allocator),
#if defined(CONFIG_UAVCAN_ARMING_CONTROLLER)
	_arming_status_controller(_node),
#endif
#if defined(CONFIG_UAVCAN_BEEP_CONTROLLER)
	_beep_controller(_node),
#endif
#if defined(CONFIG_UAVCAN_OUTPUTS_CONTROLLER)
	_esc_controller(_node),
	_servo_controller(_node),
#endif
#if defined(CONFIG_UAVCAN_HARDPOINT_CONTROLLER)
	_hardpoint_controller(_node),
#endif
#if defined(CONFIG_UAVCAN_SAFETY_STATE_CONTROLLER)
	_safety_state_controller(_node),
#endif
#if defined(CONFIG_UAVCAN_REMOTEID_CONTROLLER)
	_remoteid_controller(_node),
#endif
#if defined(CONFIG_UAVCAN_RGB_CONTROLLER)
	_rgbled_controller(_node),
#endif
	_wheel_ctrl(_node),

	_log_message_controller(_node),
	_time_sync_master(_node),
	_time_sync_slave(_node),
	_node_status_monitor(_node),
	_node_info_retriever(_node),
	_master_timer(_node),
	_param_getset_client(_node),
	_param_opcode_client(_node),
	_param_restartnode_client(_node)
{
	int res = pthread_mutex_init(&_node_mutex, nullptr);

	if (res < 0) {
		std::abort();
	}

#if defined(CONFIG_UAVCAN_OUTPUTS_CONTROLLER)
	_mixing_interface_esc.mixingOutput().setMaxTopicUpdateRate(1000000 / UavcanEscController::MAX_RATE_HZ);
	_mixing_interface_servo.mixingOutput().setMaxTopicUpdateRate(1000000 / UavcanServoController::MAX_RATE_HZ);
#endif
}

随后我的程序编译成功下载也成功但是运行后px4会卡死,我怀疑是在初始化列表的过程中把_node传入我的实例时出现问题,或者可能是_node每进行一次传入都会记录下信息并在下面三个函数中统一管理,我的函数或许因为一些暂时没有考虑到的问题不能参加统一管理所以导致卡死。
暂时未找到问题原因。

评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值