Browse Source

add socket_can

master
zhaohe 2 years ago
parent
commit
6c0265c3c5
  1. 134
      core/driver/socketcan/libsocketcan/can_netlink.h
  2. 1207
      core/driver/socketcan/libsocketcan/libsocketcan.c
  3. 61
      core/driver/socketcan/libsocketcan/libsocketcan.h
  4. 187
      core/driver/socketcan/socket_can.cpp
  5. 109
      core/driver/socketcan/socket_can.hpp
  6. 88
      core/driver/socketcan/socket_can_frame.cpp
  7. 74
      core/driver/socketcan/socket_can_frame.hpp
  8. 114
      core/driver/socketcan/socket_can_utils.cpp
  9. 44
      core/driver/socketcan/socket_can_utils.hpp
  10. 0
      core/driver/socketcan/socketcan.cpp
  11. 0
      core/driver/socketcan/socketcan.hpp
  12. 0
      core/driver/socketcan/socketcan_frame.hpp
  13. 10
      module.cmake

134
core/driver/socketcan/libsocketcan/can_netlink.h

@ -0,0 +1,134 @@
/*
* linux/can/netlink.h
*
* Definitions for the CAN netlink interface
*
* Copyright (c) 2009 Wolfgang Grandegger <wg@grandegger.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the version 2 of the GNU General Public License
* as published by the Free Software Foundation
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*/
#ifndef _UAPI_CAN_NETLINK_H
#define _UAPI_CAN_NETLINK_H
#include <linux/types.h>
/*
* CAN bit-timing parameters
*
* For further information, please read chapter "8 BIT TIMING
* REQUIREMENTS" of the "Bosch CAN Specification version 2.0"
* at http://www.semiconductors.bosch.de/pdf/can2spec.pdf.
*/
struct can_bittiming {
__u32 bitrate; /* Bit-rate in bits/second */
__u32 sample_point; /* Sample point in one-tenth of a percent */
__u32 tq; /* Time quanta (TQ) in nanoseconds */
__u32 prop_seg; /* Propagation segment in TQs */
__u32 phase_seg1; /* Phase buffer segment 1 in TQs */
__u32 phase_seg2; /* Phase buffer segment 2 in TQs */
__u32 sjw; /* Synchronisation jump width in TQs */
__u32 brp; /* Bit-rate prescaler */
};
/*
* CAN harware-dependent bit-timing constant
*
* Used for calculating and checking bit-timing parameters
*/
struct can_bittiming_const {
char name[16]; /* Name of the CAN controller hardware */
__u32 tseg1_min; /* Time segement 1 = prop_seg + phase_seg1 */
__u32 tseg1_max;
__u32 tseg2_min; /* Time segement 2 = phase_seg2 */
__u32 tseg2_max;
__u32 sjw_max; /* Synchronisation jump width */
__u32 brp_min; /* Bit-rate prescaler */
__u32 brp_max;
__u32 brp_inc;
};
/*
* CAN clock parameters
*/
struct can_clock {
__u32 freq; /* CAN system clock frequency in Hz */
};
/*
* CAN operational and error states
*/
enum can_state {
CAN_STATE_ERROR_ACTIVE = 0, /* RX/TX error count < 96 */
CAN_STATE_ERROR_WARNING, /* RX/TX error count < 128 */
CAN_STATE_ERROR_PASSIVE, /* RX/TX error count < 256 */
CAN_STATE_BUS_OFF, /* RX/TX error count >= 256 */
CAN_STATE_STOPPED, /* Device is stopped */
CAN_STATE_SLEEPING, /* Device is sleeping */
CAN_STATE_MAX
};
/*
* CAN bus error counters
*/
struct can_berr_counter {
__u16 txerr;
__u16 rxerr;
};
/*
* CAN controller mode
*/
struct can_ctrlmode {
__u32 mask;
__u32 flags;
};
#define CAN_CTRLMODE_LOOPBACK 0x01 /* Loopback mode */
#define CAN_CTRLMODE_LISTENONLY 0x02 /* Listen-only mode */
#define CAN_CTRLMODE_3_SAMPLES 0x04 /* Triple sampling mode */
#define CAN_CTRLMODE_ONE_SHOT 0x08 /* One-Shot mode */
#define CAN_CTRLMODE_BERR_REPORTING 0x10 /* Bus-error reporting */
#define CAN_CTRLMODE_FD 0x20 /* CAN FD mode */
#define CAN_CTRLMODE_PRESUME_ACK 0x40 /* Ignore missing CAN ACKs */
/*
* CAN device statistics
*/
struct can_device_stats {
__u32 bus_error; /* Bus errors */
__u32 error_warning; /* Changes to error warning state */
__u32 error_passive; /* Changes to error passive state */
__u32 bus_off; /* Changes to bus off state */
__u32 arbitration_lost; /* Arbitration lost errors */
__u32 restarts; /* CAN controller re-starts */
};
/*
* CAN netlink interface
*/
enum {
IFLA_CAN_UNSPEC,
IFLA_CAN_BITTIMING,
IFLA_CAN_BITTIMING_CONST,
IFLA_CAN_CLOCK,
IFLA_CAN_STATE,
IFLA_CAN_CTRLMODE,
IFLA_CAN_RESTART_MS,
IFLA_CAN_RESTART,
IFLA_CAN_BERR_COUNTER,
IFLA_CAN_DATA_BITTIMING,
IFLA_CAN_DATA_BITTIMING_CONST,
__IFLA_CAN_MAX
};
#define IFLA_CAN_MAX (__IFLA_CAN_MAX - 1)
#endif /* !_UAPI_CAN_NETLINK_H */

1207
core/driver/socketcan/libsocketcan/libsocketcan.c
File diff suppressed because it is too large
View File

61
core/driver/socketcan/libsocketcan/libsocketcan.h

@ -0,0 +1,61 @@
/*
* libsocketcan.h
*
* (C) 2009 Luotao Fu <l.fu@pengutronix.de>
*
* This library is free software; you can redistribute it and/or modify it under
* the terms of the GNU Lesser General Public License as published by the Free
* Software Foundation; either version 2.1 of the License, or (at your option)
* any later version.
*
* This library is distributed in the hope that it will be useful, but without
* any warranty; without even the implied warranty of merchantability or fitness
* for a particular purpose. see the gnu lesser general public license for more
* details.
*
* you should have received a copy of the gnu lesser general public license
* along with this library; if not, write to the free software foundation, inc.,
* 59 temple place, suite 330, boston, ma 02111-1307 usa
*/
#ifndef _socketcan_netlink_h
#define _socketcan_netlink_h
/**
* @file
* @brief API overview
*/
#include "can_netlink.h"
struct rtnl_link_stats64; /* from <linux/if_link.h> */
#ifdef __cplusplus
extern "C" {
#endif
int can_do_restart(const char *name);
int can_do_stop(const char *name);
int can_do_start(const char *name);
int can_set_restart_ms(const char *name, __u32 restart_ms);
int can_set_bittiming(const char *name, struct can_bittiming *bt);
int can_set_ctrlmode(const char *name, struct can_ctrlmode *cm);
int can_set_bitrate(const char *name, __u32 bitrate);
int can_set_bitrate_samplepoint(const char *name, __u32 bitrate, __u32 sample_point);
int can_get_restart_ms(const char *name, __u32 *restart_ms);
int can_get_bittiming(const char *name, struct can_bittiming *bt);
int can_get_ctrlmode(const char *name, struct can_ctrlmode *cm);
int can_get_state(const char *name, int *state);
int can_get_clock(const char *name, struct can_clock *clock);
int can_get_bittiming_const(const char *name, struct can_bittiming_const *btc);
int can_get_berr_counter(const char *name, struct can_berr_counter *bc);
int can_get_device_stats(const char *name, struct can_device_stats *cds);
int can_get_link_stats(const char *name, struct rtnl_link_stats64 *rls);
#ifdef __cplusplus
}
#endif
#endif

187
core/driver/socketcan/socket_can.cpp

@ -0,0 +1,187 @@
#include "socket_can.hpp"
using namespace iflytop;
#define DO(exptr) \
do { \
if ((exptr) != 0) { \
logger->error("do {} failed,{}", #exptr, strerror(errno)); \
goto error; \
} \
} while (0)
SocketCan::SocketCanError_t SocketCan::sendFrame(shared_ptr<SocketCanFrame> frame) {
if (frame == nullptr) {
logger->error("frame is null");
return kParamError;
}
canfd_frame_t canframe = frame->getCanFrame();
int ret = write(m_socketCanFd, &canframe, canframe.len + 8);
if (ret != (canframe.len + 8)) {
logger->error("write fail,{}", strerror(errno));
return kWriteError;
}
return kSuccess;
}
SocketCan::SocketCanError_t SocketCan::sendFrame(string framestr) {
struct canfd_frame frame = {0};
int required_mtu = 0;
required_mtu = m_socketCanUtils.parse_canframe((char *)framestr.c_str(), &frame);
if (!required_mtu) {
logger->error("Wrong CAN-frame format!");
return kErrorFrameFormat;
}
if (required_mtu > (int)CAN_MTU) {
logger->error("CAN-FD frames not supported!");
return kCANFDNotSupported;
}
logger->info("send frame:{} {} {} {} {} {}", required_mtu, frame.can_id, frame.len, frame.flags, frame.__res0, frame.__res1);
if (write(m_socketCanFd, &frame, required_mtu) != required_mtu) {
logger->error("write failed,{}", strerror(errno));
return kWriteError;
}
return kSuccess;
}
void SocketCan::initialize(shared_ptr<SocketCanConfig> socketCanConfig) { //
ZCHECK(socketCanConfig, "socketCanConfig is null");
m_socketCanConfig = socketCanConfig;
socketcanInitialize();
}
void SocketCan::startListen() { startListenThread(); }
void SocketCan::socketcanReInitialize() {}
void SocketCan::startListenThread() {
if (m_thread) {
endListenThread();
return;
}
logger->info("startListenThread");
m_thread.reset(new Thread("SocketCanThread", [this]() {
/**
* @brief call socketCanReadThreadLoop
*/
socketCanReadThreadLoop();
}));
}
void SocketCan::endListenThread() {
logger->info("endListenThread");
if (m_thread) {
m_thread->join();
m_thread = nullptr;
}
}
void SocketCan::socketcanInitialize() {
// setCanBitrate(canName, bitrate);
struct ifreq ifr = {0};
struct sockaddr_can addr = {0};
can_filter_t zerofilter = {0};
int recv_own_msgs = 0; /* 0 = disabled (default), 1 = enabled */
vector<can_filter_t> filters = m_socketCanConfig->m_canfilters;
if (!findCan(m_socketCanConfig->m_canName)) {
logger->error("can:{} not found", m_socketCanConfig->m_canName);
return;
}
if (m_thread) endListenThread();
if (m_socketCanFd > 0) socketcanDeInitialize();
logger->info("socketcanInitialize,canName:{},canBaudrate:{}", m_socketCanConfig->m_canName, m_socketCanConfig->m_canBaudrate);
// 配置socketCan波特率,注意该方法必须放在socket之前
setCanBitrate(m_socketCanConfig->m_canName, m_socketCanConfig->m_canBaudrate);
// SOCKET
m_socketCanFd = socket(PF_CAN, SOCK_RAW, CAN_RAW);
if (m_socketCanFd < 0) {
logger->error("socket failed,{}", strerror(errno));
goto error;
}
// 设置依靠名字绑定CAN设备
strcpy(ifr.ifr_name, m_socketCanConfig->m_canName.c_str());
DO(ioctl(m_socketCanFd, SIOCGIFINDEX, &ifr));
// BIND
addr.can_family = AF_CAN;
addr.can_ifindex = ifr.ifr_ifindex;
DO(bind(m_socketCanFd, (struct sockaddr *)&addr, sizeof(addr)));
// 设置过滤器
if (filters.empty()) {
filters.push_back(zerofilter);
}
DO(setsockopt(m_socketCanFd, SOL_CAN_RAW, CAN_RAW_FILTER, &zerofilter, sizeof(zerofilter)));
recv_own_msgs = 0; /* 0 = disabled (default), 1 = enabled */
DO(setsockopt(m_socketCanFd, SOL_CAN_RAW, CAN_RAW_RECV_OWN_MSGS, &recv_own_msgs, sizeof(recv_own_msgs)));
logger->info("socketcan init success");
return;
error:
logger->error("socketcan init failed");
if (m_socketCanFd > 0) {
close(m_socketCanFd);
m_socketCanFd = -1;
}
return;
}
void SocketCan::socketcanDeInitialize() {}
void SocketCan::canReadThread() {}
void SocketCan::setCanBitrate(string canName, int bitrate) {
logger->info("set can:{} bitrate:{}", canName, bitrate);
dosystem(fmt::format("ip link set {} down", canName));
dosystem(fmt::format("ip link set {} type can bitrate {}", canName, bitrate));
dosystem(fmt::format("ip link set {} up", canName));
}
bool SocketCan::findCan(string canName) { return access(fmt::format("/sys/class/net/{}", canName).c_str(), F_OK) == 0; }
void SocketCan::dosystem(string cmd) {
logger->info("do cmd:{}", cmd);
system(cmd.c_str());
}
void SocketCan::socketCanReadThreadLoop() {
ThisThread thisThread;
fd_set readfds, readFileDescriptors;
FD_ZERO(&readFileDescriptors);
FD_SET(m_socketCanFd, &readFileDescriptors);
while (!thisThread.getExitFlag()) {
canfd_frame_t canframe;
timeval waitTime;
waitTime.tv_sec = 0;
waitTime.tv_usec = 100000; // 100ms
readfds = readFileDescriptors;
int n = select(m_socketCanFd + 1, &readfds, 0, 0, &waitTime);
if (n <= 0) continue;
memset(&canframe, 0x00, sizeof(canframe));
int ret = read(m_socketCanFd, &canframe, sizeof(canframe));
if (ret < 0) {
logger->error("read failed,{}", strerror(errno));
continue;
}
shared_ptr<SocketCanFrame> socketCanFrame = SocketCanFrame::createFrame(canframe);
logger->debug("RX:{}", socketCanFrame->toString());
onSocketCanFrame(socketCanFrame);
}
}

109
core/driver/socketcan/socket_can.hpp

@ -0,0 +1,109 @@
//
// Created by zwsd
//
#pragma once
#include <fstream>
#include <iostream>
#include <list>
#include <map>
#include <memory>
#include <set>
#include <sstream>
#include <string>
#include <vector>
#include "iflytopcpp/core/spdlogfactory/logger.hpp"
#include "iflytopcpp/core/thread/thread.hpp"
#include "socket_can_frame.hpp"
#include "socket_can_utils.hpp"
/**
* @brief
*
* service: SocketCan
*
* :
* :
* :
* :
*
*/
namespace iflytop {
using namespace std;
using namespace core;
class SocketCanConfig {
public:
string m_canName;
int m_canBaudrate;
vector<can_filter_t> m_canfilters;
};
class SocketCanDeviceState {
public:
};
class SocketCan : public enable_shared_from_this<SocketCan> {
ENABLE_LOGGER(SocketCan);
unique_ptr<Thread> m_thread;
unique_ptr<Thread> m_monitorThread;
int m_socketCanFd = -1;
bool m_startListen = false;
SocketCanUtils m_socketCanUtils;
shared_ptr<SocketCanConfig> m_socketCanConfig;
public:
typedef enum {
kSuccess,
// Wrong CANFrame format!
kErrorFrameFormat,
// CAN-FD frames not supported!
kCANFDNotSupported,
kWriteError,
kParamError,
} SocketCanError_t;
public:
nod::signal<void(shared_ptr<SocketCanFrame>)> onSocketCanFrame;
SocketCan(){};
void initialize(shared_ptr<SocketCanConfig> socketCanConfig);
void startListen();
SocketCanError_t sendFrame(shared_ptr<SocketCanFrame> frame);
/**
* @brief can帧
*
* @param frame
* frame="11111111#1122334455667788" ID=0x11111111,=,=,=8,=1122334455667788
* frame="111#1122334455667788" ID=0x111, =,=,=8,=1122334455667788
* frame="111#R" ID=0x111, =,=,=0
* frame="11111111#R" ID=0x11111111,=,=,=0
* @return int
*/
SocketCanError_t sendFrame(string frame);
private:
void socketcanInitialize();
void socketcanDeInitialize();
void socketcanReInitialize();
void startListenThread();
void endListenThread();
void socketCanReadThreadLoop();
private:
void dosystem(string cmd);
void setCanBitrate(string canName, int bitrate);
bool findCan(string canName);
private:
void canReadThread();
};
} // namespace iflytop

88
core/driver/socketcan/socket_can_frame.cpp

@ -0,0 +1,88 @@
#include "socket_can_frame.hpp"
#include "iflytopcpp/core/components/stringutils.hpp"
using namespace iflytop;
shared_ptr<SocketCanFrame> SocketCanFrame::createExtDataFrame(uint32_t id, uint8_t *data, size_t len) {
shared_ptr<SocketCanFrame> canframe = make_shared<SocketCanFrame>();
if (len > 8) len = 8;
canframe->m_id = id;
canframe->m_canIdentifier = kextFrame;
canframe->m_canFrameType = kdataframe;
canframe->m_dlc = len;
memcpy(canframe->m_data, data, len);
return canframe;
}
shared_ptr<SocketCanFrame> SocketCanFrame::createStdDataFrame(uint32_t id, uint8_t *data, size_t len) {
shared_ptr<SocketCanFrame> canframe = make_shared<SocketCanFrame>();
if (len > 8) len = 8;
canframe->m_id = id;
canframe->m_canIdentifier = kstdFrame;
canframe->m_canFrameType = kdataframe;
canframe->m_dlc = len;
memcpy(canframe->m_data, data, len);
return canframe;
}
shared_ptr<SocketCanFrame> SocketCanFrame::createExtRemoteFrame(uint32_t id) {
shared_ptr<SocketCanFrame> canframe = make_shared<SocketCanFrame>();
canframe->m_id = id;
canframe->m_canIdentifier = kextFrame;
canframe->m_canFrameType = kremoteframe;
canframe->m_dlc = 0;
return canframe;
}
shared_ptr<SocketCanFrame> SocketCanFrame::createStdRemoteFrame(uint32_t id) {
shared_ptr<SocketCanFrame> canframe = make_shared<SocketCanFrame>();
canframe->m_id = id;
canframe->m_canIdentifier = kstdFrame;
canframe->m_canFrameType = kremoteframe;
canframe->m_dlc = 0;
return canframe;
}
shared_ptr<SocketCanFrame> SocketCanFrame::createFrame(canfd_frame_t frame) {
shared_ptr<SocketCanFrame> canframe = make_shared<SocketCanFrame>();
canframe->m_id = frame.can_id & ~CAN_EFF_FLAG & ~CAN_RTR_FLAG & ~CAN_ERR_FLAG;
canframe->m_canIdentifier = frame.can_id & CAN_EFF_FLAG ? kextFrame : kstdFrame;
canframe->m_canFrameType = frame.can_id & CAN_RTR_FLAG ? kremoteframe : kdataframe;
canframe->m_dlc = frame.len;
memcpy(canframe->m_data, frame.data, frame.len);
return canframe;
}
void SocketCanFrame::setCanIdentifier(can_identifier_t canIdentifier) { this->m_canIdentifier = canIdentifier; }
void SocketCanFrame::setFanFrameType(can_frame_type_t fanFrameType) { this->m_canFrameType = fanFrameType; }
void SocketCanFrame::setId(uint32_t id) { this->m_id = id; }
uint32_t SocketCanFrame::getId() { return m_id; }
can_identifier_t SocketCanFrame::getCanIdentifier() { return m_canIdentifier; }
can_frame_type_t SocketCanFrame::getFanFrameType() { return m_canFrameType; }
string SocketCanFrame::toString() { //
return fmt::format("|{:0>8x}|{:>6}|{}|{}({})|", getId(), //
getFanFrameType() == kdataframe ? "data" : "remote", //
getCanIdentifier() == kextFrame ? "ext" : "std", //
StringUtils().bytesToString(m_data, m_dlc), m_dlc);
}
canfd_frame_t SocketCanFrame::getCanFrame() {
canfd_frame_t frame;
memset(&frame, 0, sizeof(frame));
if (m_canIdentifier == kstdFrame) {
frame.can_id = (m_id & CAN_SFF_MASK);
} else {
frame.can_id = (m_id & CAN_EFF_MASK) | CAN_EFF_FLAG;
}
if (m_canFrameType == kremoteframe) {
frame.can_id |= CAN_RTR_FLAG;
frame.len = m_dlc;
} else {
frame.len = m_dlc;
memcpy(frame.data, m_data, m_dlc);
}
return frame;
}

74
core/driver/socketcan/socket_can_frame.hpp

@ -0,0 +1,74 @@
#pragma once
#include <linux/can.h>
#include <linux/can/raw.h>
#include <net/if.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <sys/ioctl.h>
#include <sys/socket.h>
#include <unistd.h>
#include <fstream>
#include <iostream>
#include <list>
#include <map>
#include <memory>
#include <set>
#include <sstream>
#include <string>
#include <vector>
#include "iflytopcpp/core/basic/nod/nod.hpp"
#include "iflytopcpp/core/spdlogfactory/logger.hpp"
#include "iflytopcpp/core/thread/thread.hpp"
namespace iflytop {
using namespace std;
using namespace core;
/*******************************************************************************
* CAN_FRAME *
*******************************************************************************/
typedef struct can_filter can_filter_t;
typedef struct canfd_frame canfd_frame_t;
typedef enum {
kstdFrame,
kextFrame,
} can_identifier_t;
typedef enum {
kdataframe,
kremoteframe,
} can_frame_type_t;
class SocketCanFrame {
private:
uint32_t m_id = 0;
can_identifier_t m_canIdentifier = kstdFrame;
can_frame_type_t m_canFrameType = kdataframe;
uint8_t m_data[8] = {0};
uint8_t m_dlc = 0;
public:
static shared_ptr<SocketCanFrame> createExtDataFrame(uint32_t id, uint8_t *data, size_t len);
static shared_ptr<SocketCanFrame> createStdDataFrame(uint32_t id, uint8_t *data, size_t len);
static shared_ptr<SocketCanFrame> createExtRemoteFrame(uint32_t id);
static shared_ptr<SocketCanFrame> createStdRemoteFrame(uint32_t id);
static shared_ptr<SocketCanFrame> createFrame(canfd_frame_t frame);
void setId(uint32_t id);
uint32_t getId();
can_frame_type_t getFanFrameType();
void setFanFrameType(can_frame_type_t fanFrameType);
can_identifier_t getCanIdentifier();
void setCanIdentifier(can_identifier_t canIdentifier);
canfd_frame_t getCanFrame();
string toString();
};
} // namespace iflytop

114
core/driver/socketcan/socket_can_utils.cpp

@ -0,0 +1,114 @@
#include "socket_can_utils.hpp"
using namespace iflytop;
using namespace std;
using namespace iflytop;
#define CANID_DELIM '#'
#define CC_DLC_DELIM '_'
#define DATA_SEPERATOR '.'
#define CAN_MAX_DLC 8
#define CAN_MAX_RAW_DLC 15
#define CAN_MAX_DLEN 8
static unsigned char asc2nibble(char c) {
if ((c >= '0') && (c <= '9')) return c - '0';
if ((c >= 'A') && (c <= 'F')) return c - 'A' + 10;
if ((c >= 'a') && (c <= 'f')) return c - 'a' + 10;
return 16; /* error */
}
uint16_t SocketCanUtils::parse_canframe(char *cs, struct canfd_frame *cf) {
/* documentation see lib.h */
int i, idx, dlen, len;
int maxdlen = CAN_MAX_DLEN;
int ret = CAN_MTU;
canid_t tmp;
len = strlen(cs);
// printf("'%s' len %d\n", cs, len);
memset(cf, 0, sizeof(*cf)); /* init CAN FD frame, e.g. LEN = 0 */
if (len < 4) return 0;
if (cs[3] == CANID_DELIM) { /* 3 digits */
idx = 4;
for (i = 0; i < 3; i++) {
if ((tmp = asc2nibble(cs[i])) > 0x0F) return 0;
cf->can_id |= (tmp << (2 - i) * 4);
}
} else if (cs[8] == CANID_DELIM) { /* 8 digits */
idx = 9;
for (i = 0; i < 8; i++) {
if ((tmp = asc2nibble(cs[i])) > 0x0F) return 0;
cf->can_id |= (tmp << (7 - i) * 4);
}
if (!(cf->can_id & CAN_ERR_FLAG)) /* 8 digits but no errorframe? */
cf->can_id |= CAN_EFF_FLAG; /* then it is an extended frame */
} else
return 0;
if ((cs[idx] == 'R') || (cs[idx] == 'r')) { /* RTR frame */
cf->can_id |= CAN_RTR_FLAG;
/* check for optional DLC value for CAN 2.0B frames */
if (cs[++idx] && (tmp = asc2nibble(cs[idx++])) <= CAN_MAX_DLEN) {
cf->len = tmp;
/* check for optional raw DLC value for CAN 2.0B frames */
if ((tmp == CAN_MAX_DLEN) && (cs[idx++] == CC_DLC_DELIM)) {
tmp = asc2nibble(cs[idx]);
if ((tmp > CAN_MAX_DLEN) && (tmp <= CAN_MAX_RAW_DLC)) {
struct can_frame *ccf = (struct can_frame *)cf;
ccf->__res1 = tmp;
}
}
}
return ret;
}
if (cs[idx] == CANID_DELIM) { /* CAN FD frame escape char '##' */
maxdlen = CANFD_MAX_DLEN;
ret = CANFD_MTU;
/* CAN FD frame <canid>##<flags><data>* */
if ((tmp = asc2nibble(cs[idx + 1])) > 0x0F) return 0;
cf->flags = tmp;
idx += 2;
}
for (i = 0, dlen = 0; i < maxdlen; i++) {
if (cs[idx] == DATA_SEPERATOR) /* skip (optional) separator */
idx++;
if (idx >= len) /* end of string => end of data */
break;
if ((tmp = asc2nibble(cs[idx++])) > 0x0F) return 0;
cf->data[i] = (tmp << 4);
if ((tmp = asc2nibble(cs[idx++])) > 0x0F) return 0;
cf->data[i] |= tmp;
dlen++;
}
cf->len = dlen;
/* check for extra DLC when having a Classic CAN with 8 bytes payload */
if ((maxdlen == CAN_MAX_DLEN) && (dlen == CAN_MAX_DLEN) && (cs[idx++] == CC_DLC_DELIM)) {
unsigned char dlc = asc2nibble(cs[idx]);
if ((dlc > CAN_MAX_DLEN) && (dlc <= CAN_MAX_RAW_DLC)) {
struct can_frame *ccf = (struct can_frame *)cf;
ccf->__res1 = dlc;
}
}
return ret;
}

44
core/driver/socketcan/socket_can_utils.hpp

@ -0,0 +1,44 @@
#pragma once
#include <linux/can.h>
#include <linux/can/raw.h>
#include <net/if.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <sys/ioctl.h>
#include <sys/socket.h>
#include <unistd.h>
#include <fstream>
#include <functional>
#include <iostream>
#include <list>
#include <map>
#include <memory>
#include <set>
#include <sstream>
#include <string>
#include <vector>
#include "iflytopcpp/core/spdlogfactory/logger.hpp"
#include "iflytopcpp/core/thread/thread.hpp"
namespace iflytop {
using namespace std;
class SocketCanUtils {
ENABLE_LOGGER(SocketCanUtils);
public:
/**
* @brief canframe
*
* @param frame
* frame="11111111#1122334455667788" ID=0x11111111,=,=,=8,=1122334455667788
* frame="111#1122334455667788" ID=0x111, =,=,=8,=1122334455667788
* frame="111#R" ID=0x111, =,=,=0
* frame="11111111#R" ID=0x11111111,=,=,=0
* @return uint16_t
*/
uint16_t parse_canframe(char *cs, struct canfd_frame *cf);
};
} // namespace iflytop

0
core/driver/socketcan/socketcan.cpp

0
core/driver/socketcan/socketcan.hpp

0
core/driver/socketcan/socketcan_frame.hpp

10
module.cmake

@ -26,9 +26,15 @@ set(DEP_SRC
dep/iflytopcpp/core/components/process/process_unix.cpp
dep/iflytopcpp/core/components/process/process.cpp
dep/iflytopcpp/core/components/timer/simple_timer.cpp
dep/iflytopcpp/core/driver/sockcanpp/CanDriver.cpp
#
dep/iflytopcpp/core/components/audio/wav_recorder.cpp)
dep/iflytopcpp/core/components/audio/wav_recorder.cpp
# driver socket_can
dep/iflytopcpp/core/driver/socketcan/libsocketcan/libsocketcan.c
dep/iflytopcpp/core/driver/socketcan/socket_can_frame.cpp
dep/iflytopcpp/core/driver/socketcan/socket_can_utils.cpp
dep/iflytopcpp/core/driver/socketcan/socket_can.cpp
#
)
set(DEP_DEFINE ${DEP_DEFINE})
set(PUBLIC_INCLUDE_DIRECTORIES ${PUBLIC_INCLUDE_DIRECTORIES}
./dep/iflytopcpp/core/spdlog/include/)
Loading…
Cancel
Save