File can_bus.hpp

License:

License BSD-3-Clause

Copyright

Copyright (c) 2019, New York University and Max Planck Gesellschaft.

Date

2019-07-11

namespace blmc_drivers

This namespace is the standard namespace of the package.

class CanBus : public blmc_drivers::CanBusInterface
#include <can_bus.hpp>

CanBus is the implementation of the CanBusInterface.

Public Functions

CanBus(const std::string &can_interface_name, const size_t &history_length = 1000)

Construct a new CanBus object.

Parameters
  • can_interface_name

  • history_length

virtual ~CanBus()

Destroy the CanBus object.

inline virtual std::shared_ptr<const CanframeTimeseries> get_output_frame() const

Getters.

Get the output frame

Returns

std::shared_ptr<const CanframeTimeseries>

inline virtual std::shared_ptr<const CanframeTimeseries> get_input_frame()

Get the input frame.

Returns

std::shared_ptr<const CanframeTimeseries>

inline virtual std::shared_ptr<const CanframeTimeseries> get_sent_input_frame()

Get the input frame thas has been sent.

Returns

std::shared_ptr<const CanframeTimeseries>

inline virtual void set_input_frame(const CanBusFrame &input_frame)

Setters.

Set the input frame

Parameters

input_frame

virtual void send_if_input_changed()

Sender.

Send the queue of message to the can network

Private Functions

void loop()

Execute the communication loop with the can bus.

void send_frame(const CanBusFrame &unstamped_can_frame)

Send input data.

Parameters

unstamped_can_frame – is a frame without id nor time.

CanBusFrame receive_frame()

Get the output frame from the bus.

Returns

CanBusFrame is the output frame data.

CanBusConnection setup_can(std::string name, uint32_t err_mask)

Setup and initialize the CanBus object.

It connects to the can bus. This method is used once in the constructor.

Parameters
  • name – is the can card name.

  • err_mask, always – used with “0” so far (TODO: Manuel explain)

Returns

CanBusConnection

Private Members

real_time_tools::SingletypeThreadsafeObject<CanBusConnection, 1> can_connection_

Attributes.

can_connection_ is the communication object allowing to send or receive can frames.

std::shared_ptr<time_series::TimeSeries<CanBusFrame>> input_

input_ is a list of time stamped frame to be send to the can network.

std::shared_ptr<time_series::TimeSeries<CanBusFrame>> sent_input_

sent_inupt_ is the list of the input already sent to the network.

std::shared_ptr<time_series::TimeSeries<CanBusFrame>> output_

output_ is the list of the frames received from the can network.

bool is_loop_active_

This boolean makes sure that the loop is not active upon destruction of the current object.

real_time_tools::RealTimeThread rt_thread_

rt_thread_ is the thread object allowing us to spawn real-time threads.

std::string log_dir_

Log directory.

std::string name_

time_log_name is the name of the loggin

Private Static Functions

static inline THREAD_FUNCTION_RETURN_TYPE loop(void *instance_pointer)

private attributes and methods

This function is an helper that allows us to launch real-time thread in xenaomai, ubunt, or rt-preempt seemlessly.

Parameters

instance_pointer

Returns

THREAD_FUNCTION_RETURN_TYPE (is void or void* depending on the OS.

class CanBusConnection
#include <can_bus.hpp>

CanBusConnection is a data structure that contains the hardware details for the connection between to can cards.

Public Members

struct sockaddr_can send_addr

send_addr is the ip address where to send the the messages.

int socket

socket is the port through which the messages will be processed

class CanBusFrame
#include <can_bus.hpp>

CanBusFrame is a class that contains a fixed sized amount of data to be send or received via the can bus.

Public Functions

inline void print() const

Public Members

std::array<uint8_t, 8> data

data is the acutal data to be sent/received.

uint8_t dlc

dlc is the size of the message.

can_id_t id

id is the id number return by the CAN bus.

class CanBusInterface : public blmc_drivers::DeviceInterface
#include <can_bus.hpp>

CanBusInterface is an abstract class that defines an API for the communication via Can bus.

Subclassed by blmc_drivers::CanBus

Public Types

typedef time_series::TimeSeries<CanBusFrame> CanframeTimeseries

CanframeTimeseries is a simple sohortcut.

Public Functions

inline virtual ~CanBusInterface()

Destroy the CanBusInterface object.

virtual std::shared_ptr<const CanframeTimeseries> get_output_frame() const = 0

getters

Get the output frame

Returns

std::shared_ptr<const CanframeTimeseries>

virtual std::shared_ptr<const CanframeTimeseries> get_input_frame() = 0

Get the input frame.

Returns

std::shared_ptr<const CanframeTimeseries>

virtual std::shared_ptr<const CanframeTimeseries> get_sent_input_frame() = 0

Get the sent input frame.

Returns

std::shared_ptr<const CanframeTimeseries>

virtual void set_input_frame(const CanBusFrame &input_frame) = 0

setters

Set the input frame saves the input frame to be sent in a queue.

Parameters

input_frame

virtual void send_if_input_changed() = 0

Sender.

send all the input frame to the can network