Skip to content

Commit ae1e3e2

Browse files
committed
inv can debug prints
1 parent c28abb1 commit ae1e3e2

File tree

5 files changed

+130
-114
lines changed

5 files changed

+130
-114
lines changed

lib/interfaces/src/InverterInterface.cpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -63,6 +63,7 @@ void InverterInterface::receive_INV_STATUS(const CAN_message_t &can_msg, unsigne
6363

6464
_feedback_data.status.new_data = true;
6565
_feedback_data.status.last_recv_millis = curr_millis;
66+
6667
}
6768

6869
void InverterInterface::receive_INV_TEMPS(const CAN_message_t &can_msg, unsigned long curr_millis)
@@ -93,6 +94,8 @@ void InverterInterface::receive_INV_DYNAMICS(const CAN_message_t &can_msg, unsig
9394
_feedback_data.motor_mechanics.actual_speed = unpacked_msg.actual_speed_rpm;
9495
_feedback_data.motor_mechanics.new_data = true;
9596
_feedback_data.motor_mechanics.last_recv_millis = curr_millis;
97+
98+
Serial.println(unpacked_msg.actual_power_w);
9699
}
97100

98101
void InverterInterface::receive_INV_POWER(const CAN_message_t &can_msg, unsigned long curr_millis)

lib/interfaces/src/VCRCANInterfaceImpl.cpp

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -23,10 +23,23 @@ void on_auxillary_can_receive(const CAN_message_t &msg) {
2323
}
2424

2525
void on_inverter_can_receive(const CAN_message_t &msg) {
26+
2627
TELEM_CAN.write(msg); // send immediately onto the telem CAN line
2728
uint8_t buf[sizeof(CAN_message_t)];
2829
memmove(buf, &msg, sizeof(msg));
2930
inverter_can_rx_buffer.push_back(buf, sizeof(CAN_message_t));
31+
32+
Serial.println("msg recvd");
33+
Serial.print("MB: "); Serial.print(msg.mb);
34+
Serial.print(" ID: 0x"); Serial.print(msg.id, HEX);
35+
Serial.print(" EXT: "); Serial.print(msg.flags.extended);
36+
Serial.print(" LEN: "); Serial.print(msg.len);
37+
Serial.print(" DATA: ");
38+
for ( uint8_t i = 0; i < 8; i++ ) {
39+
Serial.print(msg.buf[i]); Serial.print(" ");
40+
}
41+
Serial.print(" TS: "); Serial.println(msg.timestamp);
42+
3043
}
3144

3245
void on_telem_can_receive(const CAN_message_t &msg) {

platformio.ini

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -66,7 +66,7 @@ build_src_filter =
6666
+<VCR_Constants.cpp>
6767
+<../test/test_systems/test_systems.cpp>
6868
build_unflags = -std=gnu++11
69-
build_flags =
69+
build_flags = q
7070
-std=c++17
7171
-g
7272
-D TESTING_SYSTEMS

src/main.cpp

Lines changed: 112 additions & 112 deletions
Original file line numberDiff line numberDiff line change
@@ -124,117 +124,117 @@ HT_TASK::Task run_enable_pumps(HT_TASK::DUMMY_FUNCTION, enable_pumps, dashboard_
124124

125125
HT_TASK::TaskResponse debug_print(const unsigned long& sysMicros, const HT_TASK::TaskInfo& taskInfo)
126126
{
127-
// Serial.println("timestamp\t:\taccel\t:\tbrake");
128-
// Serial.print(vcr_data.interface_data.recvd_pedals_data.last_recv_millis);
129-
// Serial.print("\t:\t");
130-
// Serial.print(vcr_data.interface_data.recvd_pedals_data.pedals_data.accel_percent);
131-
// Serial.print("\t:\t");
132-
// Serial.print(vcr_data.interface_data.recvd_pedals_data.pedals_data.brake_percent);
133-
// Serial.println();
134-
// Serial.println("pedals heartbeat good:");
135-
// Serial.print(vcr_data.interface_data.recvd_pedals_data.heartbeat_ok);
136-
// Serial.println();
137-
// Serial.println();
138-
// Serial.println();
139-
// Serial.println();
140-
141-
// Serial.println("state machine state");
142-
143-
// Serial.println(vcr_data.system_data.vehicle_state_machine_state);
144-
// Serial.println("desired speeds, torq lim");
145-
// Serial.println(VCRControlsInstance::instance()._debug_dt_command.desired_speeds.FL);
146-
// Serial.println(VCRControlsInstance::instance()._debug_dt_command.torque_limits.FL);
147-
148-
// Serial.print("Drivetrain system state: ");
149-
// Serial.println(static_cast<int>(DrivetrainInstance::instance().get_state()));
150-
// Serial.print("Diagnostic FL #: ");
151-
// Serial.print(DrivetrainInstance::instance().get_status().inverter_statuses.FL.diagnostic_number);
152-
// Serial.print(" FR #: ");
153-
// Serial.print(DrivetrainInstance::instance().get_status().inverter_statuses.FR.diagnostic_number);
154-
// Serial.print(" RL #: ");
155-
// Serial.print(DrivetrainInstance::instance().get_status().inverter_statuses.RL.diagnostic_number);
156-
// Serial.print(" RR #: ");
157-
// Serial.println(DrivetrainInstance::instance().get_status().inverter_statuses.RR.diagnostic_number);
158-
159-
// Serial.print("Vehicle statemachine state: ");
160-
// Serial.println(static_cast<int>(VehicleStateMachineInstance::instance().get_state()));
161-
162-
// Serial.print("launch controller state: ");
163-
// Serial.println(static_cast<int>(VCRControlsInstance::instance().get_launch_controller().get_launch_state()));
164-
165-
// Serial.print("Start button pressed: ");
166-
// Serial.println(vcr_data.interface_data.dash_input_state.start_btn_is_pressed);
167-
168-
// Serial.print("pedal recalibrate button pressed: ");
169-
// Serial.println(vcr_data.interface_data.dash_input_state.preset_btn_is_pressed);
170-
171-
// Serial.print("mc reset button pressed: ");
172-
// Serial.println(vcr_data.interface_data.dash_input_state.mc_reset_btn_is_pressed);
173-
174-
// Serial.print("torque mode cycle button pressed: ");
175-
// Serial.println(vcr_data.interface_data.dash_input_state.mode_btn_is_pressed);
176-
177-
// Serial.println("IOExpander testing");
178-
// Serial.println("Shutdown Data");
179-
// Serial.println(vcr_data.interface_data.shutdown_sensing_data.bspd_is_ok);
180-
//Serial.println(vcr_data.interface_data.shutdown_sensing_data.k_watchdog_relay);
181-
// Serial.println(vcr_data.interface_data.shutdown_sensing_data.watchdog_is_ok);
182-
// Serial.println(vcr_data.interface_data.shutdown_sensing_data.l_bms_relay);
183-
// Serial.println(vcr_data.interface_data.shutdown_sensing_data.bms_is_ok);
184-
// Serial.println(vcr_data.interface_data.shutdown_sensing_data.m_imd_relay);
185-
// Serial.println(vcr_data.interface_data.shutdown_sensing_data.imd_is_ok);
186-
// Serial.println("Linked Data");
187-
// Serial.println(vcr_data.interface_data.ethernet_is_linked.acu_link);
188-
// Serial.println(vcr_data.interface_data.ethernet_is_linked.drivebrain_link);
189-
// Serial.println(vcr_data.interface_data.ethernet_is_linked.vcf_link);
190-
// Serial.println(vcr_data.interface_data.ethernet_is_linked.teensy_link);
191-
// Serial.println(vcr_data.interface_data.ethernet_is_linked.debug_link);
192-
// Serial.println(vcr_data.interface_data.ethernet_is_linked.ubiquiti_link);
193-
194-
195-
// Serial.print("Load Cell RR: ");
196-
// Serial.println(vcr_data.interface_data.rear_loadcell_data.RR_loadcell_analog);
197-
198-
// Serial.print("Load Cell RL: ");
199-
// Serial.println(vcr_data.interface_data.rear_loadcell_data.RL_loadcell_analog);
200-
201-
// Serial.print("SusPot RR: ");
202-
// Serial.println(vcr_data.interface_data.rear_suspot_data.RR_sus_pot_analog);
203-
204-
// Serial.print("SusPot RL: ");
205-
// Serial.println(vcr_data.interface_data.rear_suspot_data.RL_sus_pot_analog);
206-
207-
/* Drivebrain data */
208-
// Serial.print("Latest Drivebrain data: ");
209-
// Serial.print(vcr_data.interface_data.latest_drivebrain_command.torque_limits.veh_vec_data.FL);
210-
// Serial.print(" ");
211-
// Serial.print(vcr_data.interface_data.latest_drivebrain_command.torque_limits.veh_vec_data.FR);
212-
// Serial.print(" ");
213-
// Serial.print(vcr_data.interface_data.latest_drivebrain_command.torque_limits.veh_vec_data.RL);
214-
// Serial.print(" ");
215-
// Serial.println(vcr_data.interface_data.latest_drivebrain_command.torque_limits.veh_vec_data.FL);
216-
217-
/* Thermistor Data */
218-
// Serial.print("Thermistor 0 Analog: ");
219-
// Serial.print(vcr_data.interface_data.thermistor_data.thermistor_0.thermistor_analog);
220-
// Serial.print(" Thermistor 0 degrees C: ");
221-
// Serial.println(vcr_data.interface_data.thermistor_data.thermistor_0.thermistor_degrees_C);
222-
// Serial.print("Thermistor 4 Analog: ");
223-
// Serial.print(vcr_data.interface_data.thermistor_data.thermistor_4.thermistor_analog);
224-
// Serial.print(" Thermistor 4 degrees C: ");
225-
// Serial.println(vcr_data.interface_data.thermistor_data.thermistor_4.thermistor_degrees_C);
226-
// Serial.print("Thermistor 5 Analog: ");
227-
// Serial.print(vcr_data.interface_data.thermistor_data.thermistor_5.thermistor_analog);
228-
// Serial.print(" Thermistor 5 degrees C: ");
229-
// Serial.println(vcr_data.interface_data.thermistor_data.thermistor_5.thermistor_degrees_C);
230-
// Serial.print("Thermistor 6 Analog: ");
231-
// Serial.print(vcr_data.interface_data.thermistor_data.thermistor_6.thermistor_analog);
232-
// Serial.print(" Thermistor 6 degrees C: ");
233-
// Serial.println(vcr_data.interface_data.thermistor_data.thermistor_6.thermistor_degrees_C);
234-
// Serial.print("Thermistor 7 Analog: ");
235-
// Serial.print(vcr_data.interface_data.thermistor_data.thermistor_7.thermistor_analog);
236-
// Serial.print(" Thermistor 7 degrees C: ");
237-
// Serial.println(vcr_data.interface_data.thermistor_data.thermistor_7.thermistor_degrees_C);
127+
// Serial.println("timestamp\t:\taccel\t:\tbrake");
128+
// Serial.print(vcr_data.interface_data.recvd_pedals_data.last_recv_millis);
129+
// Serial.print("\t:\t");
130+
// Serial.print(vcr_data.interface_data.recvd_pedals_data.pedals_data.accel_percent);
131+
// Serial.print("\t:\t");
132+
// Serial.print(vcr_data.interface_data.recvd_pedals_data.pedals_data.brake_percent);
133+
// Serial.println();
134+
// Serial.println("pedals heartbeat good:");
135+
// Serial.print(vcr_data.interface_data.recvd_pedals_data.heartbeat_ok);
136+
// Serial.println();
137+
// Serial.println();
138+
// Serial.println();
139+
// Serial.println();
140+
141+
// Serial.println("state machine state");
142+
143+
// Serial.println(vcr_data.system_data.vehicle_state_machine_state);
144+
// Serial.println("desired speeds, torq lim");
145+
// Serial.println(VCRControlsInstance::instance()._debug_dt_command.desired_speeds.FL);
146+
// Serial.println(VCRControlsInstance::instance()._debug_dt_command.torque_limits.FL);
147+
148+
Serial.print("Drivetrain system state: ");
149+
Serial.println(static_cast<int>(DrivetrainInstance::instance().get_state()));
150+
Serial.print("Diagnostic FL #: ");
151+
Serial.print(DrivetrainInstance::instance().get_status().inverter_statuses.FL.diagnostic_number);
152+
Serial.print(" FR #: ");
153+
Serial.print(DrivetrainInstance::instance().get_status().inverter_statuses.FR.diagnostic_number);
154+
Serial.print(" RL #: ");
155+
Serial.print(DrivetrainInstance::instance().get_status().inverter_statuses.RL.diagnostic_number);
156+
Serial.print(" RR #: ");
157+
Serial.println(DrivetrainInstance::instance().get_status().inverter_statuses.RR.diagnostic_number);
158+
159+
// Serial.print("Vehicle statemachine state: ");
160+
// Serial.println(static_cast<int>(VehicleStateMachineInstance::instance().get_state()));
161+
162+
// Serial.print("launch controller state: ");
163+
// Serial.println(static_cast<int>(VCRControlsInstance::instance().get_launch_controller().get_launch_state()));
164+
165+
// Serial.print("Start button pressed: ");
166+
// Serial.println(vcr_data.interface_data.dash_input_state.start_btn_is_pressed);
167+
168+
// Serial.print("pedal recalibrate button pressed: ");
169+
// Serial.println(vcr_data.interface_data.dash_input_state.preset_btn_is_pressed);
170+
171+
// Serial.print("mc reset button pressed: ");
172+
// Serial.println(vcr_data.interface_data.dash_input_state.mc_reset_btn_is_pressed);
173+
174+
// Serial.print("torque mode cycle button pressed: ");
175+
// Serial.println(vcr_data.interface_data.dash_input_state.mode_btn_is_pressed);
176+
177+
// Serial.println("IOExpander testing");
178+
// Serial.println("Shutdown Data");
179+
// Serial.println(vcr_data.interface_data.shutdown_sensing_data.bspd_is_ok);
180+
//Serial.println(vcr_data.interface_data.shutdown_sensing_data.k_watchdog_relay);
181+
// Serial.println(vcr_data.interface_data.shutdown_sensing_data.watchdog_is_ok);
182+
// Serial.println(vcr_data.interface_data.shutdown_sensing_data.l_bms_relay);
183+
// Serial.println(vcr_data.interface_data.shutdown_sensing_data.bms_is_ok);
184+
// Serial.println(vcr_data.interface_data.shutdown_sensing_data.m_imd_relay);
185+
// Serial.println(vcr_data.interface_data.shutdown_sensing_data.imd_is_ok);
186+
// Serial.println("Linked Data");
187+
// Serial.println(vcr_data.interface_data.ethernet_is_linked.acu_link);
188+
// Serial.println(vcr_data.interface_data.ethernet_is_linked.drivebrain_link);
189+
// Serial.println(vcr_data.interface_data.ethernet_is_linked.vcf_link);
190+
// Serial.println(vcr_data.interface_data.ethernet_is_linked.teensy_link);
191+
// Serial.println(vcr_data.interface_data.ethernet_is_linked.debug_link);
192+
// Serial.println(vcr_data.interface_data.ethernet_is_linked.ubiquiti_link);
193+
194+
195+
// Serial.print("Load Cell RR: ");
196+
// Serial.println(vcr_data.interface_data.rear_loadcell_data.RR_loadcell_analog);
197+
198+
// Serial.print("Load Cell RL: ");
199+
// Serial.println(vcr_data.interface_data.rear_loadcell_data.RL_loadcell_analog);
200+
201+
// Serial.print("SusPot RR: ");
202+
// Serial.println(vcr_data.interface_data.rear_suspot_data.RR_sus_pot_analog);
203+
204+
// Serial.print("SusPot RL: ");
205+
// Serial.println(vcr_data.interface_data.rear_suspot_data.RL_sus_pot_analog);
206+
207+
/* Drivebrain data */
208+
// Serial.print("Latest Drivebrain data: ");
209+
// Serial.print(vcr_data.interface_data.latest_drivebrain_command.torque_limits.veh_vec_data.FL);
210+
// Serial.print(" ");
211+
// Serial.print(vcr_data.interface_data.latest_drivebrain_command.torque_limits.veh_vec_data.FR);
212+
// Serial.print(" ");
213+
// Serial.print(vcr_data.interface_data.latest_drivebrain_command.torque_limits.veh_vec_data.RL);
214+
// Serial.print(" ");
215+
// Serial.println(vcr_data.interface_data.latest_drivebrain_command.torque_limits.veh_vec_data.FL);
216+
217+
/* Thermistor Data */
218+
// Serial.print("Thermistor 0 Analog: ");
219+
// Serial.print(vcr_data.interface_data.thermistor_data.thermistor_0.thermistor_analog);
220+
// Serial.print(" Thermistor 0 degrees C: ");
221+
// Serial.println(vcr_data.interface_data.thermistor_data.thermistor_0.thermistor_degrees_C);
222+
// Serial.print("Thermistor 4 Analog: ");
223+
// Serial.print(vcr_data.interface_data.thermistor_data.thermistor_4.thermistor_analog);
224+
// Serial.print(" Thermistor 4 degrees C: ");
225+
// Serial.println(vcr_data.interface_data.thermistor_data.thermistor_4.thermistor_degrees_C);
226+
// Serial.print("Thermistor 5 Analog: ");
227+
// Serial.print(vcr_data.interface_data.thermistor_data.thermistor_5.thermistor_analog);
228+
// Serial.print(" Thermistor 5 degrees C: ");
229+
// Serial.println(vcr_data.interface_data.thermistor_data.thermistor_5.thermistor_degrees_C);
230+
// Serial.print("Thermistor 6 Analog: ");
231+
// Serial.print(vcr_data.interface_data.thermistor_data.thermistor_6.thermistor_analog);
232+
// Serial.print(" Thermistor 6 degrees C: ");
233+
// Serial.println(vcr_data.interface_data.thermistor_data.thermistor_6.thermistor_degrees_C);
234+
// Serial.print("Thermistor 7 Analog: ");
235+
// Serial.print(vcr_data.interface_data.thermistor_data.thermistor_7.thermistor_analog);
236+
// Serial.print(" Thermistor 7 degrees C: ");
237+
// Serial.println(vcr_data.interface_data.thermistor_data.thermistor_7.thermistor_degrees_C);
238238

239239
Serial.println();
240240

@@ -400,7 +400,7 @@ void setup() {
400400
scheduler.schedule(enqueue_coolant_temp_CAN_task);
401401
scheduler.schedule(async_main_task);
402402
scheduler.schedule(enqueue_controls_CAN_task);
403-
// scheduler.schedule(debug_state_print_task);
403+
scheduler.schedule(debug_state_print_task);
404404
scheduler.schedule(update_brakelight_task);
405405
scheduler.schedule(update_sample_flowmeter);
406406
scheduler.schedule(IOExpander_read_task);

src/main_can_test.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22

33
#include "CANInterface.h"
44

5-
FlexCAN_T4<CAN1> MAIN_CAN;
5+
FlexCAN_T4<CAN3> MAIN_CAN;
66

77
const uint32_t CAN_BAUDRATE = 500000;
88

0 commit comments

Comments
 (0)