You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
/*
* This memory is reserved for uavcan to use for queuing CAN frames.
* At 1Mbit there is approximately one CAN frame every 145 uS.
* The number of buffers sets how long you can go without calling
* node_spin_xxxx. Since our task is the only one running and the
* driver will light the fd when there is a CAN frame we can nun with
* a minimum number of buffers to conserver memory. Each buffer is
* 32 bytes. So 5 buffers costs 160 bytes and gives us a poll rate
* of ~1 mS
* 1000000/200
*/
virtual int ioctl(file *filp, int cmd, unsigned long arg);
static int start(uavcan::NodeID node_id, uint32_t bitrate);
uavcan::Node<> &get_node() { return _node; }
// TODO: move the actuator mixing stuff into the ESC controller class
static int control_callback(uintptr_t handle, uint8_t control_group, uint8_t control_index, float &input);
static UavcanNode *instance() { return _instance; }
static int getHardwareVersion(uavcan::protocol::HardwareVersion &hwver);
int fw_server(eServerAction action);
void attachITxQueueInjector(ITxQueueInjector *injector) {_tx_injector = injector;}
int list_params(int remote_node_id);
int save_params(int remote_node_id);
int set_param(int remote_node_id, const char *name, char *value);
int get_param(int remote_node_id, const char *name);
UavcanTeste _teste_controller;
int _teste_topic_sub = -1;
teste_topic_s _teste_topic ;
int reset_node(int remote_node_id);
private:
void fill_node_info();
int init(uavcan::NodeID node_id);
void node_spin_once();
int run();
int add_poll_fd(int fd); ///< add a fd to poll list, returning index into _poll_fds[]
int start_fw_server();
int stop_fw_server();
int request_fw_check();
int print_params(uavcan::protocol::param::GetSet::Response &resp);
int get_set_param(int nodeid, const char *name, uavcan::protocol::param::GetSet::Request &req);
void update_params();
void set_setget_response(uavcan::protocol::param::GetSet::Response *resp)
{
_setget_response = resp;
}
void free_setget_response(void)
{
_setget_response = nullptr;
}
int _task = -1; ///< handle to the OS task
bool _task_should_exit = false; ///< flag to indicate to tear down the CAN driver
volatile eServerAction _fw_server_action;
int _fw_server_status;
int _armed_sub = -1; ///< uORB subscription of the arming status
actuator_armed_s _armed = {}; ///< the arming request of the system
bool _is_armed = false; ///< the arming status of the actuators on the bus
int _test_motor_sub = -1; ///< uORB subscription of the test_motor status
test_motor_s _test_motor = {};
bool _test_in_progress = false;
unsigned _output_count = 0; ///< number of actuators currently available
In above file I added three new lines in Public class: UavcanTeste _teste_controller;
int _teste_topic_sub = -1;
teste_topic_s _teste_topic ;
UavcanTeste a class in uavcan_main.hpp.
When i tried to build it, using px4_fmu-v5_default , it throws me an error uavcan::TimerEventForwarder _master_timer;
I am new to using UAVCAN. I am not able to understand why I am facing this error. I followed this code in documentation which built the same code successfully in px4_fmu-v2_default . Any pointers on this?
The text was updated successfully, but these errors were encountered:
/****************************************************************************
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.
****************************************************************************/
/**
*/
#pragma once
#include <px4_config.h>
#include "uavcan_driver.hpp"
#include <uavcan/helpers/heap_based_pool_allocator.hpp>
#include <uavcan/protocol/global_time_sync_master.hpp>
#include <uavcan/protocol/global_time_sync_slave.hpp>
#include <uavcan/protocol/node_status_monitor.hpp>
#include <uavcan/protocol/param/GetSet.hpp>
#include <uavcan/protocol/param/ExecuteOpcode.hpp>
#include <uavcan/protocol/RestartNode.hpp>
#include <drivers/device/device.h>
#include <perf/perf_counter.h>
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/actuator_outputs.h>
#include <uORB/topics/actuator_armed.h>
#include <uORB/topics/test_motor.h>
#include <uORB/topics/actuator_direct.h>
#include "actuators/teste_actuator.hpp"
#include "actuators/esc.hpp"
#include "actuators/hardpoint.hpp"
#include "sensors/sensor_bridge.hpp"
#include "uavcan_servers.hpp"
#include "allocator.hpp"
#define NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN 4
// we add two to allow for actuator_direct and busevent
#define UAVCAN_NUM_POLL_FDS (NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN+2)
/**
*/
class UavcanNode : public cdev::CDev
{
static constexpr unsigned MaxBitRatePerSec = 1000000;
static constexpr unsigned bitPerFrame = 148;
static constexpr unsigned FramePerSecond = MaxBitRatePerSec / bitPerFrame;
static constexpr unsigned FramePerMSecond = ((FramePerSecond / 1000) + 1);
public:
typedef UAVCAN_DRIVER::CanInitHelper CanInitHelper;
enum eServerAction {None, Start, Stop, CheckFW, Busy};
private:
void fill_node_info();
int init(uavcan::NodeID node_id);
void node_spin_once();
int run();
int add_poll_fd(int fd); ///< add a fd to poll list, returning index into _poll_fds[]
int start_fw_server();
int stop_fw_server();
int request_fw_check();
int print_params(uavcan::protocol::param::GetSet::Response &resp);
int get_set_param(int nodeid, const char *name, uavcan::protocol::param::GetSet::Request &req);
void update_params();
void set_setget_response(uavcan::protocol::param::GetSet::Response *resp)
{
_setget_response = resp;
}
void free_setget_response(void)
{
_setget_response = nullptr;
}
};
In above file I added three new lines in Public class:
UavcanTeste _teste_controller;
int _teste_topic_sub = -1;
teste_topic_s _teste_topic ;
UavcanTeste a class in uavcan_main.hpp.
When i tried to build it, using px4_fmu-v5_default , it throws me an error uavcan::TimerEventForwarder _master_timer;
I am new to using UAVCAN. I am not able to understand why I am facing this error. I followed this code in documentation which built the same code successfully in px4_fmu-v2_default . Any pointers on this?
The text was updated successfully, but these errors were encountered: