Skip to content

Commit

Permalink
working on ca
Browse files Browse the repository at this point in the history
  • Loading branch information
RCMast3r committed Sep 14, 2024
1 parent 411149b commit 7458e73
Show file tree
Hide file tree
Showing 9 changed files with 87 additions and 162 deletions.
2 changes: 1 addition & 1 deletion lib/interfaces/include/HytechCANInterface.h
Original file line number Diff line number Diff line change
Expand Up @@ -170,7 +170,7 @@ void process_ring_buffer(BufferType &rx_buffer, const InterfaceType &interfaces,
case VN_LAT_LON_CANID:
interfaces.vn_interface->retrieve_lat_lon_CAN(recvd_msg);
break;
case VN_GPS_TIME_CANID:
case VN_GPS_TIME_MSG_CANID:
interfaces.vn_interface->retrieve_gps_time_CAN(recvd_msg);
break;
case VN_STATUS_CANID:
Expand Down
46 changes: 0 additions & 46 deletions lib/interfaces/include/ParameterInterface.h

This file was deleted.

27 changes: 7 additions & 20 deletions lib/interfaces/include/ProtobufMsgInterface.h
Original file line number Diff line number Diff line change
@@ -1,19 +1,16 @@
#ifndef PROTOBUFMSGINTERFACE
#define PROTOBUFMSGINTERFACE

#include "ht_eth.pb.h"
#include "pb_encode.h"
#include "pb_decode.h"
#include "pb_common.h"
#include "ParameterInterface.h"
#include "circular_buffer.h"
#include "NativeEthernet.h"
#include "MCU_rev15_defs.h"
#include "InterfaceParams.h"

struct ETHInterfaces
{
ParameterInterface* param_interface;
};

using recv_function_t = void (*)(const uint8_t* buffer, size_t packet_size, ETHInterfaces& interfaces);
Expand Down Expand Up @@ -50,27 +47,17 @@ bool handle_ethernet_socket_send_pb(EthernetUDP* socket, const pb_struct& msg, c
return true;
}

//
void recv_pb_stream_union_msg(const uint8_t *buffer, size_t packet_size, ETHInterfaces& interfaces)

template <typename pb_msg_type>
std::pair<pb_msg_type, bool> recv_pb_stream_msg(const uint8_t *buffer, size_t packet_size, ETHInterfaces& interfaces, const pb_msgdesc_t * desc_pointer)
{
pb_istream_t stream = pb_istream_from_buffer(buffer, packet_size);
HT_ETH_Union msg = HT_ETH_Union_init_zero;
if (pb_decode(&stream, HT_ETH_Union_fields, &msg))
pb_msg_type msg = {};
if (pb_decode(&stream, desc_pointer, &msg))
{
Serial.println("decoded!");

switch (msg.which_type_union)
{
case HT_ETH_Union_config__tag:
interfaces.param_interface->update_config(msg.type_union.config_);
break;
case HT_ETH_Union_get_config__tag:
interfaces.param_interface->set_params_need_sending();
break;
default:
break;
}
return {msg, true};
}
return {msg, };
}


Expand Down
10 changes: 5 additions & 5 deletions lib/interfaces/include/VectornavInterface.tpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,8 +50,8 @@ void VNInterface<message_queue>::retrieve_lat_lon_CAN(CAN_message_t &recvd_msg)

template<typename message_queue>
void VNInterface<message_queue>::retrieve_gps_time_CAN(CAN_message_t &recvd_msg) {
VN_GPS_TIME_t gps_time_data;
Unpack_VN_GPS_TIME_hytech(&gps_time_data, recvd_msg.buf, recvd_msg.len);
VN_GPS_TIME_MSG_t gps_time_data;
Unpack_VN_GPS_TIME_MSG_hytech(&gps_time_data, recvd_msg.buf, recvd_msg.len);
vn_data.gps_time = gps_time_data.vn_gps_time;
}

Expand All @@ -72,9 +72,9 @@ void VNInterface<message_queue>::retrieve_vn_ecef_pos_xy_CAN(CAN_message_t &recv

template <typename message_queue>
void VNInterface<message_queue>::retrieve_vn_ecef_pos_z_CAN(CAN_message_t &recvd_msg) {
VN_ECEF_POS_Z_t ecef_z;
Unpack_VN_ECEF_POS_Z_hytech(&ecef_z, recvd_msg.buf, recvd_msg.len);
vn_data.ecef_coords[2] = HYTECH_vn_ecef_pos_z_ro_fromS(ecef_z.vn_ecef_pos_z_ro);
VN_ECEF_POS_Z_MSG_t ecef_z;
Unpack_VN_ECEF_POS_Z_MSG_hytech(&ecef_z, recvd_msg.buf, recvd_msg.len);
vn_data.ecef_coords[2] = HYTECH_vn_ecef_pos_z_msg_ro_fromS(ecef_z.vn_ecef_pos_z_ro);
}

template <typename message_queue>
Expand Down
24 changes: 12 additions & 12 deletions lib/interfaces/src/TelemetryInterface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -177,10 +177,10 @@ void TelemetryInterface::update_drivetrain_torque_telem_CAN_msg(
// TODO: change this to use actual torque values from inverter
// Torque current just temporary for gearbox seal validation
DRIVETRAIN_TORQUE_TELEM_t torque;
torque.fl_motor_torque_ro = HYTECH_fl_motor_torque_ro_toS(fl->get_torque_current());
torque.fr_motor_torque_ro = HYTECH_fr_motor_torque_ro_toS(fr->get_torque_current());
torque.rl_motor_torque_ro = HYTECH_rl_motor_torque_ro_toS(rl->get_torque_current());
torque.rr_motor_torque_ro = HYTECH_rr_motor_torque_ro_toS(rr->get_torque_current());
torque.fl_motor_torque = fl->get_torque_current();
torque.fr_motor_torque = fr->get_torque_current();
torque.rl_motor_torque = rl->get_torque_current();
torque.rr_motor_torque = rr->get_torque_current();

enqueue_new_CAN<DRIVETRAIN_TORQUE_TELEM_t>(&torque, &Pack_DRIVETRAIN_TORQUE_TELEM_hytech);
}
Expand Down Expand Up @@ -219,16 +219,16 @@ void TelemetryInterface::update_steering_status_CAN_msg(const float steering_sys
const uint8_t steering_encoder_status,
const uint8_t steering_analog_status)
{
// STEERING_SYSTEM_REPORT_t msg;
STEERING_SYSTEM_REPORT_t msg;

// msg.steering_system_angle_ro = HYTECH_steering_system_angle_ro_toS(steering_system_angle);
// msg.steering_encoder_angle_ro = HYTECH_steering_encoder_angle_ro_toS(filtered_angle_encoder);
// msg.steering_analog_angle_ro = HYTECH_steering_analog_angle_ro_toS(filtered_angle_analog);
// msg.steering_system_status = steering_system_status;
// msg.steering_encoder_status = steering_encoder_status;
// msg.steering_analog_status = steering_analog_status;
msg.steering_system_angle_ro = HYTECH_steering_system_angle_ro_toS(steering_system_angle);
msg.steering_encoder_angle_ro = HYTECH_steering_encoder_angle_ro_toS(filtered_angle_encoder);
msg.steering_analog_angle_ro = HYTECH_steering_analog_angle_ro_toS(filtered_angle_analog);
msg.steering_system_status = steering_system_status;
msg.steering_encoder_status = steering_encoder_status;
msg.steering_analog_status = steering_analog_status;

// enqueue_new_CAN<STEERING_SYSTEM_REPORT_t>(&msg, &Pack_STEERING_SYSTEM_REPORT_hytech);
enqueue_new_CAN<STEERING_SYSTEM_REPORT_t>(&msg, &Pack_STEERING_SYSTEM_REPORT_hytech);
}

/* Send CAN messages */
Expand Down
2 changes: 0 additions & 2 deletions lib/state_machine/include/MCUStateMachine.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,8 +13,6 @@
#include "AMSInterface.h"
#include "PrintLogger.h"

// #include "IMDInterface.h"

enum class CAR_STATE
{
STARTUP = 0,
Expand Down
108 changes: 54 additions & 54 deletions lib/systems/include/CASESystem.h
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
#include "SteeringSystem.h"
#include "MCUStateMachine.h"
#include "ProtobufMsgInterface.h"
#include "ParameterInterface.h"
// #include "ParameterInterface.h"

struct CASEConfiguration
{
Expand Down Expand Up @@ -167,59 +167,59 @@ class CASESystem
/// @brief configuration function to determine what CASE is using / turn on and off different features within CASE
/// @param config the configuration struct we will be setting

void update_config_from_param_interface(ParameterInterface &param_interface_ref)
{
config cfg = param_interface_ref.get_config();
config_.AbsoluteTorqueLimit = cfg.AbsoluteTorqueLimit;
config_.yaw_pid_p = cfg.yaw_pid_p;
config_.yaw_pid_i = cfg.yaw_pid_i;
config_.yaw_pid_d = cfg.yaw_pid_d;
config_.tcs_pid_p_lowerBound_front = cfg.tcs_pid_p_lowerBound_front;
config_.tcs_pid_p_upperBound_front = cfg.tcs_pid_p_upperBound_front;
config_.tcs_pid_p_lowerBound_rear = cfg.tcs_pid_p_lowerBound_rear;
config_.tcs_pid_p_upperBound_rear = cfg.tcs_pid_p_upperBound_rear;
config_.tcs_pid_i = cfg.tcs_pid_i;
config_.tcs_pid_d = cfg.tcs_pid_d;
config_.useLaunch = cfg.useLaunch;
config_.usePIDTV = cfg.usePIDTV;
config_.useTCSLimitedYawPID = cfg.useTCSLimitedYawPID;
config_.useNormalForce = cfg.useNormalForce;
config_.useTractionControl = cfg.useTractionControl;
config_.usePowerLimit = cfg.usePowerLimit;
config_.usePIDPowerLimit = cfg.usePIDPowerLimit;
config_.useDecoupledYawBrakes = cfg.useDecoupledYawBrakes;
config_.useDiscontinuousYawPIDBrakes = cfg.useDiscontinuousYawPIDBrakes;
config_.tcsSLThreshold = cfg.tcsSLThreshold;
config_.launchSL = cfg.launchSL;
config_.launchDeadZone = cfg.launchDeadZone;
config_.launchVelThreshold = cfg.launchVelThreshold;
config_.tcsVelThreshold = cfg.tcsVelThreshold;
config_.yawPIDMaxDifferential = cfg.yawPIDMaxDifferential;
config_.yawPIDErrorThreshold = cfg.yawPIDErrorThreshold;
config_.yawPIDVelThreshold = cfg.yawPIDVelThreshold;
config_.yawPIDCoastThreshold = cfg.yawPIDCoastThreshold;
config_.yaw_pid_brakes_p = cfg.yaw_pid_brakes_p;
config_.yaw_pid_brakes_i = cfg.yaw_pid_brakes_i;
config_.yaw_pid_brakes_d = cfg.yaw_pid_brakes_d;
config_.decoupledYawPIDBrakesMaxDIfference = cfg.decoupledYawPIDBrakesMaxDIfference;
config_.discontinuousBrakesPercentThreshold = cfg.discontinuousBrakesPercentThreshold;
config_.TorqueMode = cfg.TorqueMode;
config_.RegenLimit = cfg.RegenLimit;
config_.useNoRegen5kph = cfg.useNoRegen5kph;
config_.useTorqueBias = cfg.useTorqueBias;
config_.DriveTorquePercentFront = cfg.DriveTorquePercentFront;
config_.BrakeTorquePercentFront = cfg.BrakeTorquePercentFront;
config_.MechPowerMaxkW = cfg.MechPowerMaxkW;
config_.launchLeftRightMaxDiff = cfg.launchLeftRightMaxDiff;
config_.tcs_pid_lower_rpm_front = cfg.tcs_pid_lower_rpm_front;
config_.tcs_pid_upper_rpm_front = cfg.tcs_pid_upper_rpm_front;
config_.tcs_pid_lower_rpm_rear = cfg.tcs_pid_lower_rpm_rear;
config_.tcs_pid_upper_rpm_rear = cfg.tcs_pid_upper_rpm_rear;
config_.maxNormalLoadBrakeScalingFront = cfg.maxNormalLoadBrakeScalingFront;
config_.max_rpm = cfg.max_rpm;
config_.max_regen_torque = cfg.max_regen_torque;
config_.max_torque = cfg.max_torque;
}
// void update_config_from_param_interface(ParameterInterface &param_interface_ref)
// {
// config cfg = param_interface_ref.get_config();
// config_.AbsoluteTorqueLimit = cfg.AbsoluteTorqueLimit;
// config_.yaw_pid_p = cfg.yaw_pid_p;
// config_.yaw_pid_i = cfg.yaw_pid_i;
// config_.yaw_pid_d = cfg.yaw_pid_d;
// config_.tcs_pid_p_lowerBound_front = cfg.tcs_pid_p_lowerBound_front;
// config_.tcs_pid_p_upperBound_front = cfg.tcs_pid_p_upperBound_front;
// config_.tcs_pid_p_lowerBound_rear = cfg.tcs_pid_p_lowerBound_rear;
// config_.tcs_pid_p_upperBound_rear = cfg.tcs_pid_p_upperBound_rear;
// config_.tcs_pid_i = cfg.tcs_pid_i;
// config_.tcs_pid_d = cfg.tcs_pid_d;
// config_.useLaunch = cfg.useLaunch;
// config_.usePIDTV = cfg.usePIDTV;
// config_.useTCSLimitedYawPID = cfg.useTCSLimitedYawPID;
// config_.useNormalForce = cfg.useNormalForce;
// config_.useTractionControl = cfg.useTractionControl;
// config_.usePowerLimit = cfg.usePowerLimit;
// config_.usePIDPowerLimit = cfg.usePIDPowerLimit;
// config_.useDecoupledYawBrakes = cfg.useDecoupledYawBrakes;
// config_.useDiscontinuousYawPIDBrakes = cfg.useDiscontinuousYawPIDBrakes;
// config_.tcsSLThreshold = cfg.tcsSLThreshold;
// config_.launchSL = cfg.launchSL;
// config_.launchDeadZone = cfg.launchDeadZone;
// config_.launchVelThreshold = cfg.launchVelThreshold;
// config_.tcsVelThreshold = cfg.tcsVelThreshold;
// config_.yawPIDMaxDifferential = cfg.yawPIDMaxDifferential;
// config_.yawPIDErrorThreshold = cfg.yawPIDErrorThreshold;
// config_.yawPIDVelThreshold = cfg.yawPIDVelThreshold;
// config_.yawPIDCoastThreshold = cfg.yawPIDCoastThreshold;
// config_.yaw_pid_brakes_p = cfg.yaw_pid_brakes_p;
// config_.yaw_pid_brakes_i = cfg.yaw_pid_brakes_i;
// config_.yaw_pid_brakes_d = cfg.yaw_pid_brakes_d;
// config_.decoupledYawPIDBrakesMaxDIfference = cfg.decoupledYawPIDBrakesMaxDIfference;
// config_.discontinuousBrakesPercentThreshold = cfg.discontinuousBrakesPercentThreshold;
// config_.TorqueMode = cfg.TorqueMode;
// config_.RegenLimit = cfg.RegenLimit;
// config_.useNoRegen5kph = cfg.useNoRegen5kph;
// config_.useTorqueBias = cfg.useTorqueBias;
// config_.DriveTorquePercentFront = cfg.DriveTorquePercentFront;
// config_.BrakeTorquePercentFront = cfg.BrakeTorquePercentFront;
// config_.MechPowerMaxkW = cfg.MechPowerMaxkW;
// config_.launchLeftRightMaxDiff = cfg.launchLeftRightMaxDiff;
// config_.tcs_pid_lower_rpm_front = cfg.tcs_pid_lower_rpm_front;
// config_.tcs_pid_upper_rpm_front = cfg.tcs_pid_upper_rpm_front;
// config_.tcs_pid_lower_rpm_rear = cfg.tcs_pid_lower_rpm_rear;
// config_.tcs_pid_upper_rpm_rear = cfg.tcs_pid_upper_rpm_rear;
// config_.maxNormalLoadBrakeScalingFront = cfg.maxNormalLoadBrakeScalingFront;
// config_.max_rpm = cfg.max_rpm;
// config_.max_regen_torque = cfg.max_regen_torque;
// config_.max_torque = cfg.max_torque;
// }
float get_rpm_setpoint(float final_torque)
{
if (final_torque > 0)
Expand Down
3 changes: 1 addition & 2 deletions platformio.ini
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,6 @@
lib_deps_shared =
Nanopb
git+ssh://git@github.com/hytech-racing/CASE_lib.git#v49
https://github.com/hytech-racing/HT_params/releases/download/2024-05-05T13_33_07/ht_eth_pb_lib.tar.gz
https://github.com/hytech-racing/shared_firmware_types.git#feb3b83
https://github.com/hytech-racing/shared_firmware_systems.git#af96a63

Expand Down Expand Up @@ -59,7 +58,7 @@ lib_deps =
https://github.com/tonton81/FlexCAN_T4
https://github.com/ssilverman/QNEthernet#v0.26.0
https://github.com/RCMast3r/hytech_can#testing_new_inv_ids
https://github.com/hytech-racing/HT_CAN/releases/download/90/can_lib.tar.gz
https://github.com/hytech-racing/HT_CAN/releases/download/121/can_lib.tar.gz

[env:test_can_on_teensy]
lib_ignore =
Expand Down
27 changes: 7 additions & 20 deletions src/main.cpp
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
/* Include files */
/* System Includes*/
#include <Arduino.h>
#include "ParameterInterface.h"
// #include "ParameterInterface.h"
/* Libraries */
#include "FlexCAN_T4.h"
#include "HyTech_CAN.h"
Expand Down Expand Up @@ -175,8 +175,7 @@ OrbisBR10 steering1(&Serial5);
// /*
// INTERFACES
// */
ParameterInterface param_interface;
ETHInterfaces ethernet_interfaces = {&param_interface};
ETHInterfaces ethernet_interfaces = {};
VNInterface<CircularBufferType> vn_interface(&CAN3_txBuffer);
DashboardInterface dashboard(&CAN3_txBuffer);
AMSInterface ams_interface(&CAN3_txBuffer, SOFTWARE_OK);
Expand Down Expand Up @@ -446,9 +445,6 @@ void loop()

fsm.tick_state_machine(curr_tick.millis, car_state_inst);

// give the state of the car to the param interface
param_interface.update_car_state(fsm.get_state());

// tick safety system
safety_system.software_shutdown(curr_tick);

Expand Down Expand Up @@ -492,8 +488,11 @@ void loop()
Serial.println(ams_interface.get_filtered_min_cell_voltage());
Serial.print("Filtered max cell temp: ");
Serial.println(ams_interface.get_filtered_max_cell_temp());
Serial.print("Current TC index: ");
Serial.println(static_cast<int>(torque_controller_mux.get_tc_mux_status().current_controller_mode_));
Serial.print("Current TC error: ");
Serial.println(static_cast<int>(torque_controller_mux.get_tc_mux_status().current_error));
Serial.println();

Serial.println();
}

Expand Down Expand Up @@ -677,7 +676,6 @@ void tick_all_systems(const SysTick_s &current_system_tick)
dashboard.startButtonPressed(),
vn_interface.get_vn_struct().vn_status);

// case_system.update_config_from_param_interface(param_interface);
}

void handle_ethernet_interface_comms()
Expand All @@ -686,17 +684,6 @@ void handle_ethernet_interface_comms()
// via the union message. this is a little bit cursed ngl.
// TODO un fuck this and make it more sane
// Serial.println("bruh");
handle_ethernet_socket_receive(&protobuf_recv_socket, &recv_pb_stream_union_msg, ethernet_interfaces);
// handle_ethernet_socket_receive(&protobuf_recv_socket, &recv_pb_stream_union_msg, ethernet_interfaces);

// this is just kinda here i know.
if (param_interface.params_need_sending())
{
// Serial.println("handling ethernet");
auto config = param_interface.get_config();
if (!handle_ethernet_socket_send_pb(&protobuf_send_socket, config, config_fields))
{
// TODO this means that something bad has happend
}
param_interface.reset_params_need_sending();
}
}

0 comments on commit 7458e73

Please sign in to comment.