Skip to content

Commit

Permalink
#9 update basic structure for CAN
Browse files Browse the repository at this point in the history
  • Loading branch information
dongdongO committed May 6, 2024
1 parent 9b75e2a commit a3844f2
Show file tree
Hide file tree
Showing 6 changed files with 88 additions and 43 deletions.
37 changes: 22 additions & 15 deletions control_ws/src/stanley/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,7 +1,12 @@
cmake_minimum_required(VERSION 3.5)
project(stanley)

# 기본 C++20 설정
# Default to C99
if(NOT CMAKE_C_STANDARD)
set(CMAKE_C_STANDARD 99)
endif()

# Default to C20
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 20)
endif()
Expand All @@ -10,6 +15,10 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

if(POLICY CMP0148)
cmake_policy(SET CMP0148 OLD)
endif()

# ROS 2 패키지 의존성 찾기
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
Expand All @@ -19,30 +28,26 @@ find_package(tf2 REQUIRED)
find_package(tf2_geometry_msgs REQUIRED)
find_package(example_interfaces REQUIRED)

include(ExternalProject)
# ExternalProject_Add을 사용하여 dbcppp 라이브러리 빌드
ExternalProject_Add(dbcppp_build
SOURCE_DIR ${CMAKE_CURRENT_SOURCE_DIR}/include/stanley/dbcppp
BINARY_DIR ${CMAKE_CURRENT_SOURCE_DIR}/include/stanley/dbcppp/build
CONFIGURE_COMMAND ${CMAKE_COMMAND} ..
BUILD_COMMAND ${MAKE}
INSTALL_COMMAND ""
TEST_COMMAND ""
)
find_package(Boost REQUIRED)

ament_package()

include_directories(
include/${PROJECT_NAME}
include/stanley/dbcppp/include # dbcppp 헤더 파일 위치
include/${PROJECT_NAME}/dbcppp/src
include/${PROJECT_NAME}/dbcppp/include
)

FILE(GLOB CANProtocol include/${PROJECT_NAME}/dbcppp/src/*.cpp)

add_executable(${PROJECT_NAME}
src/main.cpp
src/control.cpp
src/controller/stanley.cpp
src/canprotocol/can_protocol.cpp
${CANProtocol}
)

add_dependencies(${PROJECT_NAME} dbcppp_build) # dbcppp가 먼저 빌드되도록 의존성 추가

ament_target_dependencies(${PROJECT_NAME}
rclcpp
nav_msgs
Expand All @@ -57,4 +62,6 @@ install(TARGETS
DESTINATION lib/${PROJECT_NAME}
)

ament_package()
target_link_libraries(${PROJECT_NAME}
${Boost}
)
Original file line number Diff line number Diff line change
@@ -1,34 +1,28 @@
#pragma once

#include "utils/car_struct.h"
#include "utils/msg_structs.h"

#include "dbcppp/include/dbcppp/Network.h"

#include <iostream>
#include <fstream>
#include <unordered_map>
#include <cstring>
#include <linux/can.h>
#include <linux/can/raw.h>
#include <sys/socket.h>
#include <sys/ioctl.h>
#include <net/if.h>
#include <unistd.h>
#include <iostream>
#include <fstream>
#include <unordered_map>
#include <memory>
#include <chrono>
#include <string>
#include <unordered_map>

#include "dbcppp/Network.h"

class CANSender {
public:
CANSender(const std::string& dbc_file, const std::string& can_interface);
~CANSender();
void sendSpeedMessage(double speed);

private:
int sock;
uint64_t target_message_id;
double speed_value;
std::shared_ptr<const dbcppp::INetwork> net;
std::unique_ptr<dbcppp::INetwork> net;
std::unordered_map<uint64_t, const dbcppp::IMessage*> messages;
};

4 changes: 2 additions & 2 deletions control_ws/src/stanley/include/stanley/control.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@

#include "controller/stanley.hpp"

// #include "canprotocol/can_protocol.hpp"
#include "canprotocol/can_protocol.hpp"

#include "rclcpp/rclcpp.hpp"
#include "nav_msgs/msg/path.hpp"
Expand All @@ -27,7 +27,7 @@ class Control : public rclcpp::Node {
private:
Stanley controller;

// std::unique_ptr<CANReceiver> can_receiver;
std::unique_ptr<CANSender> can_sender;

std::vector<Path> refPoses;
Pose currPose;
Expand Down
43 changes: 43 additions & 0 deletions control_ws/src/stanley/include/stanley/utils/example.dbc
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
VERSION ""

NS_ :
NS_DESC_
CM_
BA_DEF_
BA_
VAL_
CAT_DEF_
CAT_
FILTER
BA_DEF_DEF_
EV_DATA_
ENVVAR_DATA_
SGTYPE_
SGTYPE_VAL_
BA_DEF_SGTYPE_
BA_SGTYPE_
SIG_TYPE_REF_
VAL_TABLE_
SIG_GROUP_
SIG_VALTYPE_
SIGTYPE_VALTYPE_
BO_TX_BU_
BA_DEF_REL_
BA_REL_
BA_DEF_DEF_REL_
BU_SG_REL_
BU_EV_REL_
BU_BO_REL_
SG_MUL_VAL_

BS_:

BU_: PCM

BO_ 255 SpeedMessage1: 8 PCM
SG_ Speed : 0|16@1+ (1,0) [0|65535] "" PCM

BO_ 254 SpeedMessage2: 8 PCM
SG_ Speed : 0|16@1+ (1,0) [0|65535] "" PCM

CM_ "Example DBC file with two messages using the same data structure but different IDs.";
21 changes: 11 additions & 10 deletions control_ws/src/stanley/src/canprotocol/can_protocol.cpp
Original file line number Diff line number Diff line change
@@ -1,15 +1,14 @@
// CANReceiver.cpp
#include "CANReceiver.hpp"
#include "canprotocol/can_protocol.hpp"

CANSender::CANSender(const std::string& dbc_file, const std::string& can_interface)
: target_message_id(255), speed_value(10.0) {
CANSender::CANSender(const std::string& dbc_file, const std::string& can_interface) {
std::ifstream idbc(dbc_file);
this->net = dbcppp::INetwork::LoadDBCFromIs(idbc);
if (!this->net) {
throw std::runtime_error("Failed to parse DBC file.");
}

for (const auto& msg : this->net->Messages()) {
std::cout << "Msg ID : " << msg.Id() << std::endl;
this->messages[msg.Id()] = &msg;
}

Expand All @@ -26,23 +25,25 @@ CANSender::CANSender(const std::string& dbc_file, const std::string& can_interfa
addr.can_family = AF_CAN;
addr.can_ifindex = ifr.ifr_ifindex;
bind(this->sock, (struct sockaddr *)&addr, sizeof(addr));

this->target_message_id = 255;
}

CANSender::~CANSender() {
close(sock);
}

void CANSender::sendSpeedMessage(double speed) {
auto iter = messages.find(target_message_id);
std::unordered_map<uint64_t, const dbcppp::IMessage*>::iterator iter = messages.find(target_message_id);
if (iter == messages.end()) {
throw std::runtime_error("Message with ID 255 not found in DBC.");
}

const auto& msg = *iter->second;
const dbcppp::IMessage& msg = *(iter->second);
std::vector<uint8_t> frame_data(8, 0);
for (const auto& sig : msg.Signals()) {
for (const dbcppp::ISignal& sig : msg.Signals()) {
if (sig.Name() == "Speed") {
auto raw_value = sig.PhysToRaw(speed);
double raw_value = sig.PhysToRaw(speed);
sig.Encode(raw_value, frame_data.data());
}
}
Expand All @@ -52,9 +53,9 @@ void CANSender::sendSpeedMessage(double speed) {
frame.can_dlc = frame_data.size();
std::memcpy(frame.data, frame_data.data(), frame_data.size());

int nbytes = write(sock, &frame, sizeof(struct can_frame));
ssize_t nbytes = write(sock, &frame, sizeof(struct can_frame));
if (nbytes != sizeof(struct can_frame)) {
std::cerr << "Error while sending frame" << std::endl;
throw std::runtime_error("Error while sending frame.");
} else {
std::cout << "Message sent successfully: Speed = " << speed << std::endl;
}
Expand Down
4 changes: 2 additions & 2 deletions control_ws/src/stanley/src/control.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ Control::Control() : rclcpp::Node("vehicle_control") {
this->controller = Stanley(k, ks);

// Initialize CAN receiver
// this->can_receiver = std::make_unique<CANReceiver>("../example.dbc", "vcan0");
this->can_sender = std::make_unique<CANSender>("src/stanley/include/stanley/utils/example.dbc", "vcan0");

// Subscribe
path_subscription_ = this->create_subscription<nav_msgs::msg::Path>(
Expand Down Expand Up @@ -84,7 +84,7 @@ void Control::publisher_timer_callback() {

this->publish_drive(this->speedCommand, this->steerCommand);

// this->can_receiver->receiveMessages();
this->can_sender->sendSpeedMessage(this->speedCommand);
}

void Control::publish_drive(float speed, float steer) {
Expand Down

0 comments on commit a3844f2

Please sign in to comment.