Classes | |
class | CanFileResolutionHelper |
struct | CanMatrixElement |
class | HardwareCanFilterInterpretMessage |
Converts tCanMessage to InterpretedCanMessage. More... | |
class | HardwareCanFilterMessageMap |
class | HardwareCanSinkCanfile |
class | HardwareCanSinkPeak |
class | HardwareCanSourceCanfile |
class | HardwareCanSourcePeak |
class | HardwareCanSourceTest |
struct | InterpretedCanMessage |
class | tCanDevice |
class | tCanDeviceDummy |
class | tCanDeviceT |
class | tCanFilterMessages |
class | tCanMatrixParser |
struct | tCanMessage |
Implements a struct representing a can message. More... | |
class | tCanMessageMetaDumper |
class | tException |
class | tHardwareCanSinkFactory |
Typedefs | |
typedef std::map< unsigned int, std::vector< CanMatrixElement > > | CanMatrix |
typedef std::map< unsigned, CanMessageStamped > | CanMessageMap |
Maps CAN IDs to the latest received message for each ID. | |
typedef boost::shared_ptr < const CanMessageMap > | CanMessageMapConstPtr |
Convenience shared pointer shorthand for CanMessageMap (const version). | |
typedef boost::shared_ptr < CanMessageMap > | CanMessageMapPtr |
Convenience shared pointer shorthand for CanMessageMap. | |
typedef icl_core::Stamped < tCanMessage > | CanMessageStamped |
typedef icl_sourcesink::DataSink < tCanMessage > | HardwareCanSink |
Base type for all sinks providing tCanMessage data. | |
typedef icl_sourcesink::DataSource < tCanMessage > | HardwareCanSource |
Base type for all sources providing tCanMessage data. | |
typedef std::vector < InterpretedCanMessage > | InterpretedCanMessages |
typedef int | tCanDescriptor |
typedef tCanDeviceT < tCanDescriptor > | tCanDeviceImpl |
Enumerations | |
enum | Hardware_Exception { eHARDWARE_ERROR, ePEAK_DEVICE_ERROR, eTHREAD_ERROR, eMESSAGE_ERROR, eFILE_ERROR } |
Functions | |
WORD | BaudRateSpecifier (unsigned int baud_rate) |
bool | CanDescriptorValid (tCanDescriptor can_device) |
int | CanDeviceClose (tCanDescriptor) |
tCanDescriptor | CanDeviceOpen (const char *device_name, int flags, unsigned char acceptance_code, unsigned char acceptance_mask, unsigned int baud_rate, unsigned send_fifo_size, unsigned receive_fifo_size) |
Open a can device and set parameters. | |
int | CanDeviceReceive (tCanDescriptor, tCanMessage &) |
int | CanDeviceReset (tCanDescriptor) |
int | CanDeviceSend (tCanDescriptor, const tCanMessage &) |
bool | CanDriverLxrtSupport () |
no support for LXRT available | |
const char * | CanDriverName () |
int | CanFifoReceive (int device_id, int user, tCanMessage *msg) |
Receive a message via CAN-FIFO. | |
int | CanFifoReset (int device_id) |
Reset a CAN-device. | |
int | CanFifoSend (int device_id, const tCanMessage *msg) |
Send a message via CAN-FIFO. | |
void | constructCanMessageData (unsigned char *_data, int value, const unsigned int start_bit, const unsigned int signal_length, bool little_endian) |
int | CreateCanFifoUser (int device_id, unsigned acceptance_code, unsigned acceptance_mask, unsigned int baud_rate, unsigned send_fifo_size, unsigned receive_fifo_size) |
Creates a can FIFO in kernel space. | |
ICL_HARDWARE_CAN_IMPORT_EXPORT | DECLARE_LOG_STREAM_OPERATOR (boost::posix_time::ptime) DECLARE_LOG_STREAM_IMPORT_EXPORT(CAN |
int | DestroyCanFifoUser (int device_id, int user_id) |
Destroys a can FIFO in kernel space. | |
tCanDescriptor | InvalidCanDescriptor () |
std::ostream & | operator<< (std::ostream &os, const tCanMessage &msg) |
std::ostream & | operator<< (std::ostream &os, InterpretedCanMessages const &interpreted_can_messages) |
std::ostream & | operator<< (std::ostream &stream, const CanMatrix &can_matrix) |
double | parseCanMessage (const tCanMessage &message, const unsigned int start_bit, const unsigned int signal_length, const bool little_endian, const bool signedness, const double factor, const double offset) |
template<typename T > | |
static bool | parseCanMessage (const tCanMessage &message, const unsigned int start_bit, const unsigned int signal_length, const T factor, const T offset, const T lower_border, const T upper_border, const bool little_endian, const bool signedness, T &data) |
template<typename T > | |
static bool | parseCanMessage (const tCanMessage &message, const CanMatrixElement &matrix, T &data) |
Variables | |
ICL_HARDWARE_CAN_IMPORT_EXPORT | ICL_HARDWARE_CAN_IMPORT_EXPORT |
static tCanDescriptor | no_can_instances = 0 |
typedef std::map<unsigned int, std::vector<CanMatrixElement> > icl_hardware::can::CanMatrix |
Definition at line 69 of file tCanMatrixParser.h.
typedef std::map<unsigned, CanMessageStamped> icl_hardware::can::CanMessageMap |
Maps CAN IDs to the latest received message for each ID.
Definition at line 81 of file tCanMessage.h.
typedef boost::shared_ptr<const CanMessageMap> icl_hardware::can::CanMessageMapConstPtr |
Convenience shared pointer shorthand for CanMessageMap (const version).
Definition at line 85 of file tCanMessage.h.
typedef boost::shared_ptr<CanMessageMap> icl_hardware::can::CanMessageMapPtr |
Convenience shared pointer shorthand for CanMessageMap.
Definition at line 83 of file tCanMessage.h.
A time-stamped CAN message. Replaces the obsolete tCanMessageTimed.
Definition at line 79 of file tCanMessage.h.
typedef icl_sourcesink::DataSink<tCanMessage> icl_hardware::can::HardwareCanSink |
Base type for all sinks providing tCanMessage data.
Definition at line 38 of file HardwareCanSink.h.
typedef icl_sourcesink::DataSource<tCanMessage> icl_hardware::can::HardwareCanSource |
Base type for all sources providing tCanMessage data.
Definition at line 38 of file HardwareCanSource.h.
typedef std::vector<InterpretedCanMessage> icl_hardware::can::InterpretedCanMessages |
Definition at line 48 of file InterpretedCanMessage.h.
typedef HANDLE icl_hardware::can::tCanDescriptor |
Definition at line 35 of file UseDummyCan.h.
Definition at line 58 of file tCanDevice.cpp.
Known exception types
Definition at line 46 of file tException.h.
WORD icl_hardware::can::BaudRateSpecifier | ( | unsigned int | baud_rate | ) | [inline] |
Definition at line 61 of file UsePeakCan.h.
bool icl_hardware::can::CanDescriptorValid | ( | tCanDescriptor | can_device | ) | [inline] |
Definition at line 38 of file UseDummyCan.h.
int icl_hardware::can::CanDeviceClose | ( | tCanDescriptor | _can_device | ) | [inline] |
Definition at line 62 of file UseDummyCan.h.
tCanDescriptor icl_hardware::can::CanDeviceOpen | ( | const char * | device_name, |
int | flags, | ||
unsigned char | acceptance_code, | ||
unsigned char | acceptance_mask, | ||
unsigned int | baud_rate, | ||
unsigned | send_fifo_size, | ||
unsigned | receive_fifo_size | ||
) | [inline] |
Open a can device and set parameters.
Function for open a can device and setting the corresponding parameters via ioctl.
device_name | The linux device name of the can device (e.g. '/dev/pcan0') |
flags | Flags for the linux open() call (e.g. 'O_RDWR|O_NONBLOCK') |
acceptance_code | The acceptance_code of the CAN-card (ignored for peak can) |
acceptance_mask | The acceptance_mask of the CAN-card (ignored for peak can) |
baud_rate | Baud rate for can communication in kbits |
send_fifo_size | Size of the can driver send fifo. (ignored for peak can) |
receive_fifo_size | Size of the can driver receive fifo. (ignored for peak can) Returns the file descriptor of the can device on success, -1 on failure. |
Be aware: the CAN-card parameters (acceptance_code, acceptance_mask, baud_rate) are set globally for the CAN-card and so for all registered users so far!
Be aware: If there are more than one FIFO-user, make sure all users call their read() function periodically. Otherwhise the FIFO is running full so that NO
user is able to receive further data any more.
Definition at line 53 of file UseDummyCan.h.
int icl_hardware::can::CanDeviceReceive | ( | tCanDescriptor | _can_device, |
tCanMessage & | msg | ||
) | [inline] |
Read from the the device handle. RET can take any of the following: CAN_ERR_QRCVEMPTY in case no data was read -1 in case a select function of the system failed.. -1 in case the system ioctl fails (basic way to read the interface). 0 in case of succes
Read from the the device handle. RET can take any of the following: CAN_ERR_QRCVEMPTY in case no data was read -1 in case a select function of the system failed.. -1 in case the system ioctl fails (basic way to read the interface). 0 in case of succes
Definition at line 72 of file UseDummyCan.h.
int icl_hardware::can::CanDeviceReset | ( | tCanDescriptor | _can_device | ) | [inline] |
Definition at line 77 of file UseDummyCan.h.
int icl_hardware::can::CanDeviceSend | ( | tCanDescriptor | _can_device, |
const tCanMessage & | msg | ||
) | [inline] |
Definition at line 67 of file UseDummyCan.h.
bool icl_hardware::can::CanDriverLxrtSupport | ( | ) | [inline] |
no support for LXRT available
Definition at line 35 of file UseCanNoLxrt.h.
const char * icl_hardware::can::CanDriverName | ( | ) | [inline] |
Definition at line 48 of file UseDummyCan.h.
int icl_hardware::can::CanFifoReceive | ( | int | device_id, |
int | user, | ||
tCanMessage * | msg | ||
) | [inline] |
Receive a message via CAN-FIFO.
Definition at line 64 of file UseCanNoLxrt.h.
int icl_hardware::can::CanFifoReset | ( | int | device_id | ) | [inline] |
Reset a CAN-device.
Definition at line 72 of file UseCanNoLxrt.h.
int icl_hardware::can::CanFifoSend | ( | int | device_id, |
const tCanMessage * | msg | ||
) | [inline] |
Send a message via CAN-FIFO.
Definition at line 57 of file UseCanNoLxrt.h.
void icl_hardware::can::constructCanMessageData | ( | unsigned char * | _data, |
int | value, | ||
const unsigned int | start_bit, | ||
const unsigned int | signal_length, | ||
bool | little_endian | ||
) |
Definition at line 39 of file CanMessageHelper.h.
int icl_hardware::can::CreateCanFifoUser | ( | int | device_id, |
unsigned | acceptance_code, | ||
unsigned | acceptance_mask, | ||
unsigned int | baud_rate, | ||
unsigned | send_fifo_size, | ||
unsigned | receive_fifo_size | ||
) | [inline] |
Creates a can FIFO in kernel space.
Definition at line 41 of file UseCanNoLxrt.h.
ICL_HARDWARE_CAN_IMPORT_EXPORT icl_hardware::can::DECLARE_LOG_STREAM_OPERATOR | ( | boost::posix_time::ptime | ) |
int icl_hardware::can::DestroyCanFifoUser | ( | int | device_id, |
int | user_id | ||
) | [inline] |
Destroys a can FIFO in kernel space.
Definition at line 50 of file UseCanNoLxrt.h.
tCanDescriptor icl_hardware::can::InvalidCanDescriptor | ( | ) | [inline] |
Definition at line 43 of file UseDummyCan.h.
ICL_HARDWARE_CAN_IMPORT_EXPORT std::ostream & icl_hardware::can::operator<< | ( | std::ostream & | os, |
const tCanMessage & | msg | ||
) |
Definition at line 30 of file StreamOperators.cpp.
ICL_HARDWARE_CAN_IMPORT_EXPORT std::ostream & icl_hardware::can::operator<< | ( | std::ostream & | os, |
InterpretedCanMessages const & | interpreted_can_messages | ||
) |
Definition at line 38 of file InterpretedCanMessage.cpp.
ICL_HARDWARE_CAN_IMPORT_EXPORT std::ostream & icl_hardware::can::operator<< | ( | std::ostream & | stream, |
const CanMatrix & | can_matrix | ||
) |
Definition at line 324 of file tCanMatrixParser.cpp.
double icl_hardware::can::parseCanMessage | ( | const tCanMessage & | message, |
const unsigned int | start_bit, | ||
const unsigned int | signal_length, | ||
const bool | little_endian, | ||
const bool | signedness, | ||
const double | factor, | ||
const double | offset | ||
) |
Definition at line 79 of file CanMessageHelper.h.
static bool icl_hardware::can::parseCanMessage | ( | const tCanMessage & | message, |
const unsigned int | start_bit, | ||
const unsigned int | signal_length, | ||
const T | factor, | ||
const T | offset, | ||
const T | lower_border, | ||
const T | upper_border, | ||
const bool | little_endian, | ||
const bool | signedness, | ||
T & | data | ||
) | [static] |
Definition at line 203 of file CanMessageHelper.h.
static bool icl_hardware::can::parseCanMessage | ( | const tCanMessage & | message, |
const CanMatrixElement & | matrix, | ||
T & | data | ||
) | [static] |
Definition at line 223 of file CanMessageHelper.h.
tCanDescriptor icl_hardware::can::no_can_instances = 0 [static] |
Definition at line 36 of file UseDummyCan.h.