提交 1036cbbd 编写于 作者: W wangjia 提交者: Qi Luo

neolix canbus

上级 5d20ecde
......@@ -219,6 +219,25 @@ py_proto_library(
],
)
cc_proto_library(
name = "neolix_edu_cc_proto",
deps = [
":neolix_edu_proto",
],
)
proto_library(
name = "neolix_edu_proto",
srcs = ["neolix_edu.proto"],
)
py_proto_library(
name = "neolix_edu_py_pb2",
deps = [
":neolix_edu_proto",
],
)
cc_proto_library(
name = "chassis_detail_cc_proto",
deps = [
......@@ -235,6 +254,7 @@ proto_library(
":devkit_proto",
":ge3_proto",
":lexus_proto",
":neolix_edu_proto",
":transit_proto",
":wey_proto",
":zhongyun_proto",
......@@ -251,6 +271,7 @@ py_proto_library(
":devkit_py_pb2",
":ge3_py_pb2",
":lexus_py_pb2",
":neolix_edu_py_pb2",
":transit_py_pb2",
":wey_py_pb2",
":zhongyun_py_pb2",
......
......@@ -11,6 +11,7 @@ import "modules/canbus/proto/lexus.proto";
import "modules/canbus/proto/transit.proto";
import "modules/canbus/proto/wey.proto";
import "modules/canbus/proto/zhongyun.proto";
import "modules/canbus/proto/neolix_edu.proto";
message ChassisDetail {
enum Type {
......@@ -42,6 +43,7 @@ message ChassisDetail {
optional Zhongyun zhongyun = 23;
optional Ch ch = 24;
optional Devkit devkit = 25;
optional Neolix_edu neolix_edu = 26;
// Reserve fields for other vehicles
optional apollo.common.VehicleID vehicle_id = 101;
}
......
syntax = "proto2";
package apollo.canbus;
message Aeb_systemstate_11 {
// Report Message
// 0x00:read only;0x01:brake enable [] [0|1]
optional int32 aeb_state = 1;
// 0x00:off;0x01:on [] [0|1]
optional bool aeb_brakestate = 2;
// 0x0:Nomal;0x1:Level 1;0x2:Level 2;0x3:Level 3;0x4:Level 4;0x5:Level 5;0x6:Reserved;0x7:Reserved [] [0|5]
optional int32 faultrank = 3;
// [] [0|120]
optional int32 currenttemperature = 4;
// 0x0:Normal;0x1:ActivateBrake [] [0|1]
optional bool pas_f1_stop = 5;
// 0x0:Normal;0x1:ActivateBrake [] [0|1]
optional bool pas_f2_stop = 6;
// 0x0:Normal;0x1:ActivateBrake [] [0|1]
optional bool pas_f3_stop = 7;
// 0x0:Normal;0x1:ActivateBrake [] [0|1]
optional bool pas_f4_stop = 8;
// 0x0:Normal;0x1:ActivateBrake [] [0|1]
optional bool pas_b1_stop = 9;
// 0x0:Normal;0x1:ActivateBrake [] [0|1]
optional bool pas_b2_stop = 10;
// 0x0:Normal;0x1:ActivateBrake [] [0|1]
optional bool pas_b3_stop = 11;
// 0x0:Normal;0x1:ActivateBrake [] [0|1]
optional bool pas_b4_stop = 12;
// [] [0|15]
optional int32 aeb_livecounter_rear = 13;
// [bit] [0|255]
optional int32 aeb_cheksum = 14;
}
message Vcu_vehicle_fault_response_201 {
// Report Message
// 0x0: no error;0x1: level 1 error;0x2: level 2 error;0x3: level 3 error;0x4: level 4 error;0x5: level 5 error [] [0|0]
optional int32 vehicle_error_indicationsvcu = 1;
// 0x0: no error;0x1: level 1 error;0x2: level 2 error;0x3: level 3 error;0x4: level 4 error;0x5: level 5 error [] [0|0]
optional int32 brake_system_errorehb = 2;
// 0x0: no error;0x1: level 1 error;0x2: level 2 error;0x3: level 3 error;0x4: level 4 error;0x5: level 5 error [] [0|0]
optional int32 eps_error = 3;
// 0x0: no error;0x1: level 1 error;0x2: level 2 error;0x3: level 3 error;0x4: level 4 error;0x5: level 5 error [] [0|0]
optional int32 motor_error = 4;
// 0x0: no error;0x1: level 1 error;0x2: level 2 error;0x3: level 3 error;0x4: level 4 error;0x5: level 5 error [] [0|0]
optional int32 epb_error = 5;
// 0x0: no error;0x1: level 1 error;0x2: level 2 error;0x3: level 3 error;0x4: level 4 error;0x5: level 5 error [] [0|0]
optional int32 high_voltage_battery_errorbcu = 6;
// 0x0:Normal;0x1:Failure [] [0|0]
optional bool automode_exit_reason_losscommuni = 7;
// 0x0:Normal;0x1:Failure [] [0|0]
optional bool automode_exit_reason_reqsignalno = 8;
// 0x0:Normal;0x1:Failure [] [0|0]
optional bool automode_exit_reason_low_power = 9;
// 0x0:Normal;0x1:Failure [] [0|0]
optional bool automode_exit_reason_highvolt = 10;
// 0x0:Normal;0x1:Failure [] [0|0]
optional bool automode_exit_reason_vehicle_flt = 11;
// 0x0:Normal;0x1:Failure [] [0|0]
optional bool automode_exit_reason_press_emerg = 12;
// 0x0:Normal;0x1:Failure [] [0|0]
optional bool automode_exit_reason_press_remot = 13;
// 0x0:Normal;0x1:Failure [] [0|0]
optional bool automode_exit_reason_pdu_control = 14;
// [] [0|0]
optional int32 vcu_faultrept_alivecounter = 15;
// [] [0|0]
optional int32 vcu_faultrept_checksum = 16;
}
message Vcu_powerstatus_214 {
// Report Message
// 0x0:OFF;0x1:IG_ON;0x2:Power_ON;0x3:Auto_ON;0x4:Reserved;0x5:Reserved;0x6:Reserved;0x7:Reserved [bit] [0|7]
optional int32 vcu_powermode = 1;
// 0x0:Not Available;0x1:Invalid;0x2:Valid;0x3:Reserved [bit] [0|3]
optional int32 vcu_powermodevalid = 2;
// 0x0:NotActivate;0x1:Activate [bit] [0|1]
optional bool replacebatterystateindication = 3;
// [bit] [0|15]
optional int32 vcu_driverinfo_alivecounter = 4;
// [bit] [0|255]
optional int32 vcu_driverinfo_checksum = 5;
}
message Ads_light_horn_command_310 {
// Control Message
// 0x0:disable ;0x1:enable [bit] [0|1]
optional bool turn_right_light_command = 1;
// 0x0:disable ;0x1:enable ;0x2-0x3:Reserved [bit] [0|1]
optional bool turn_left_light_command = 2;
// [bit] [0|1]
optional bool horn_command = 3;
// 0x0:Off;0x1:LowBeam;0x2:HighBeam [bit] [0|1]
optional int32 beam_command = 4;
// [] [0|0]
optional int32 auto_drivercmd_alivecounter = 5;
// [] [0|0]
optional int32 auto_drivercmd_checksum = 6;
}
message Ads_brake_command_46 {
// Control Message
// 0x0:disable ;0x1:enable [] [0|0]
optional bool drive_enable = 1;
// [] [0|0]
optional int32 auto_brake_command = 2;
// 0x0:Release ;0x1:Apply [] [0|0]
optional bool auto_parking_command = 3;
// 0x0:off;0x1:on [] [0|0]
optional bool epb_rampauxiliarycommand = 4;
// [] [0|0]
optional int32 auto_drivercmd_alivecounter = 5;
// [] [0|0]
optional int32 auto_drivercmd_checksum = 6;
}
message Vcu_brake_report_47 {
// Report Message
enum Control_mode_respType {
CONTROL_MODE_RESP_STANDBY = 0;
CONTROL_MODE_RESP_AUTO_DRIVE = 1;
CONTROL_MODE_RESP_NET_DRIVE = 2;
CONTROL_MODE_RESP_REMOTE_CONTROL = 3;
CONTROL_MODE_RESP_EMERGENCY_BRAKE = 4;
}
// 0x0:disable;0x1:enable [] [0|0]
optional bool brake_enable_resp = 1;
// 0x0:Standby;0x1:auto drive;0x2:net drive;0x3:remote control;0x4:emergency brake;0x5~0x7:Reserved [bit] [0|7]
optional Control_mode_respType control_mode_resp = 2;
// 0x0:disable;0x1:enable [] [0|0]
optional bool vcu_real_brake_valid = 3;
// [] [0|0]
optional int32 vcu_real_brake = 4;
// 0x0:EPB_Released;0x1:EPB_Applied;0x2:EPB_Releasing;0x3:EPB_Fault;0x4:EPB_Applying [] [0|0]
optional int32 vcu_real_parking_status = 5;
// 0x0:disable;0x1:enable [] [0|0]
optional bool vcu_real_parking_valid = 6;
// 0x0:off;0x1:on [] [0|0]
optional bool rampauxiliaryindication = 7;
// [°] [0|45]
optional double vehicleslope = 8;
// [] [0|0]
optional int32 vcu_brakerept_alivecounter = 9;
// [] [0|0]
optional int32 vcu_brakerept_checksum = 10;
}
message Vcu_eps_report_57 {
// Report Message
enum Control_mode_respType {
CONTROL_MODE_RESP_STANDBY = 0;
CONTROL_MODE_RESP_AUTO_DRIVE = 1;
CONTROL_MODE_RESP_NET_DRIVE = 2;
CONTROL_MODE_RESP_REMOTE_CONTROL = 3;
CONTROL_MODE_RESP_EMERGENCY_BRAKE = 4;
}
// 0x0:disable;0x1:enable [] [0|0]
optional bool drive_enable_resp = 1;
// 0x0:Standby;0x1:auto drive;0x2:net drive;0x3:remote control;0x4:emergency brake;0x5~0x7:Reserved [] [0|7]
optional Control_mode_respType control_mode_resp = 2;
// 0x0:not overflow;0x1:overflow [] [0|0]
optional bool vcu_eps_report = 3;
// ; [] [0|0]
optional double vcu_real_angle = 4;
// 0x0:disable;0x1:enable [] [0|0]
optional bool vcu_real_angle_valid = 5;
// 0x0:disable;0x1:enable; [] [0|0]
optional bool vcu_target_angle_valid = 6;
// [deg] [-380|380]
optional double vcu_target_angle = 7;
// [] [0|0]
optional int32 vcu_eps_rept_alivecounter = 8;
// [] [0|0]
optional int32 vcu_eps_rept_checksum = 9;
}
message Ads_eps_command_56 {
// Control Message
// 0x0:disable ;0x1:enable [] [0|0]
optional bool drive_enable = 1;
// [] [0|0]
optional double auto_target_angle = 2;
// [] [0|0]
optional int32 auto_drivercmd_alivecounter = 3;
// [] [0|0]
optional int32 auto_drivercmd_checksum = 4;
}
message Ads_drive_command_50 {
// Control Message
enum Auto_shift_commandType {
AUTO_SHIFT_COMMAND_N = 0;
AUTO_SHIFT_COMMAND_D = 1;
AUTO_SHIFT_COMMAND_R = 2;
AUTO_SHIFT_COMMAND_RESERVED = 3;
}
// 0x0:disable ;0x1:enable [] [0|0]
optional bool drive_enable = 1;
// 0x0:N ;0x1:D ;0x2:R ;0x3:Reserved [] [0|3]
optional Auto_shift_commandType auto_shift_command = 2;
// [] [0|0]
optional double auto_drive_torque = 3;
// [] [0|0]
optional int32 auto_drivercmd_alivecounter = 4;
// [] [0|0]
optional int32 auto_drivercmd_checksum = 5;
}
message Vcu_drive_report_52 {
// Report Message
enum Control_mode_respType {
CONTROL_MODE_RESP_STANDBY = 0;
CONTROL_MODE_RESP_AUTO_DRIVE = 1;
CONTROL_MODE_RESP_NET_DRIVE = 2;
CONTROL_MODE_RESP_REMOTE_CONTROL = 3;
CONTROL_MODE_RESP_EMERGENCY_BRAKE = 4;
}
enum Vcu_real_shiftType {
VCU_REAL_SHIFT_N = 0;
VCU_REAL_SHIFT_D = 1;
VCU_REAL_SHIFT_R = 2;
VCU_REAL_SHIFT_RESERVED = 3;
}
// 0x0:disable;0x1:enable [] [0|0]
optional bool drive_enable_resp = 1;
// 0x0:Standby;0x1:auto drive;0x2:net drive;0x3:remote control;0x4:emergency brake;0x5~0x7:Reserved [] [0|7]
optional Control_mode_respType control_mode_resp = 2;
// 0x0:N档;0x1:D档;0x2:R档;0x3:Reserved [] [0|3]
optional Vcu_real_shiftType vcu_real_shift = 3;
// 0x0:disable;0x1:enable [] [0|0]
optional bool vcu_real_shift_valid = 4;
// 0x0:disable;0x1:enable [] [0|0]
optional bool vcu_real_torque_valid = 5;
// [Nm] [0|0]
optional double vcu_real_torque = 6;
// 0x0:disable;0x1:enable [] [0|0]
optional bool vcu_limitedtorquemode = 7;
// [] [0|0]
optional int32 vcu_driverept_alivecounter = 8;
// [] [0|0]
optional int32 vcu_driverept_checksum = 9;
}
message Ads_diagnosis_628 {
// Control Message
// 0x0:Nomal;0x1:Level 1;0x2:Level 2;0x3:Level 3;0x4:Level 4;0x5:Level 5;0x6:Reserved;0x7:Reserved [bit] [0|5]
optional int32 faultrank = 1;
// [] [0|65535]
optional int32 adas_fault_code = 2;
// [bit] [0|255]
optional int32 adas_softwareversion = 3;
// [bit] [0|255]
optional int32 adas_hardwareversion = 4;
}
message Vcu_nm_401 {
// Report Message
// 0x0:Inactive;0x1:Active [bit] [0|1]
optional bool vcu_sleepcommand = 1;
}
message Vcu_vehicle_status_report_101 {
// Report Message
enum Control_mode_respType {
CONTROL_MODE_RESP_STANDBY = 0;
CONTROL_MODE_RESP_AUTO_DRIVE = 1;
CONTROL_MODE_RESP_NET_DRIVE = 2;
CONTROL_MODE_RESP_REMOTE_CONTROL = 3;
CONTROL_MODE_RESP_EMERGENCY_BRAKE = 4;
}
// 0x0:disable;0x1:enable [] [0|0]
optional bool drive_enable_resp = 1;
// 0x0:Disconnect;0x1:Connect [] [0|0]
optional bool vcu_highvoltagecircuitstate = 2;
// 0x0: Disable;0x1:Enable [] [0|0]
optional bool vcu_dcdc_enabledstates = 3;
// 0x0:Standby;0x1:auto drive;0x2:net drive;0x3:remote control;0x4:emergency brake;0x5~0x7:Reserved [] [0|7]
optional Control_mode_respType control_mode_resp = 4;
// [Km/h] [0|460.69]
optional double vcu_vehicle_speed = 5;
// 0x0:Reserved;0x1:Start;0x2:Stop;0x3:Invalid [] [0|0]
optional int32 vcu_lowbatterychargingfunctionst = 6;
// [%] [0|100]
optional int32 vcu_display_soc = 7;
// [] [0|0]
optional double vcu_motor_speed = 8;
// 0x0:Standby Status;0x1:Forward Mode;0x2:Reverse Mode [] [0|0]
optional int32 vcu_motor_direction = 9;
// 0x0:disable;0x1:enable [] [0|0]
optional bool vcu_motor_speed_valid = 10;
// [] [0|0]
optional int32 vcu_statusrept_alivecounter = 11;
// [] [0|0]
optional int32 vcu_statusrept_checksum = 12;
}
message Vcu_vehicle_info_response_502 {
// Report Message
// [] [0|16777215]
optional int32 vehicle_softwareversion_indicati = 1;
// [] [0|15]
optional int32 project = 2;
// [] [0|15]
optional int32 manufacturer = 3;
// [] [0|255]
optional int32 year = 4;
// [] [1|12]
optional int32 month = 5;
// [] [1|31]
optional int32 day = 6;
// [] [0|32767]
optional int32 vehicle_serial_number = 7;
}
message Aeb_diagnosis1_626 {
// Report Message
// [bit] [0.0|255.0]
optional double aeb_softwareversion = 1;
// [bit] [0.0|255.0]
optional double aeb_hardwareversion = 2;
}
message Aeb_diagresp_718 {
// Report Message
// [bit] [0.0|1.0]
optional bool aeb_diagresp = 1;
}
message Pas_1st_data_311 {
// Report Message
// phy=int*2;0xFF:no obstacle [cm] [0|510]
optional double pasdistance4 = 1;
// phy=int*2;0xFF:no obstacle [cm] [0|510]
optional double pasdistance3 = 2;
// 0x0:Invalid;0x1:Valid [bit] [0|1]
optional bool pas_f1_status = 3;
// 0x0:Invalid;0x1:Valid [bit] [0|1]
optional bool pas_f2_status = 4;
// 0x0:Invalid;0x1:Valid [bit] [0|1]
optional bool pas_f3_status = 5;
// 0x0:Invalid;0x1:Valid [bit] [0|1]
optional bool pas_f4_status = 6;
// phy=int*2;0xFF:no obstacle [cm] [0|510]
optional double pasdistance2 = 7;
// [cm] [0|510]
optional double pasdistance1 = 8;
}
message Pas_2nd_data_312 {
// Report Message
// 0x0:Invalid;0x1:Valid [bit] [0.0|1.0]
optional bool pas_b1_status = 1;
// 0x0:Invalid;0x1:Valid [bit] [0.0|1.0]
optional bool pas_b2_status = 2;
// 0x0:Invalid;0x1:Valid [bit] [0.0|1.0]
optional bool pas_b3_status = 3;
// 0x0:Invalid;0x1:Valid [bit] [0.0|1.0]
optional bool pas_b4_status = 4;
// phy=int*2;0xFF:no obstacle [cm] [0.0|510.0]
optional double pasdistance1 = 5;
// phy=int*2;0xFF:no obstacle [cm] [0.0|510.0]
optional double pasdistance2 = 6;
// phy=int*2;0xFF:no obstacle [cm] [0.0|510.0]
optional double pasdistance3 = 7;
// phy=int*2;0xFF:no obstacle [cm] [0.0|510.0]
optional double pasdistance4 = 8;
}
message Aeb_wheelimpulse_355 {
// Report Message
// 0x0:Invalid;0x1:Valid [bit] [0.0|1023.0]
optional double flimpulse = 1;
// 0x0:Invalid;0x1:Valid [bit] [0.0|1.0]
optional bool flimpulsevalid = 2;
// [km/h] [0.0|1023.0]
optional double frimpulse = 3;
// [km/h] [0.0|1.0]
optional bool frimpulsevalid = 4;
// 0x0:Invalid;0x1:Valid [bit] [0.0|1023.0]
optional double rlimpulse = 5;
// 0x0:Invalid;0x1:Valid [bit] [0.0|1.0]
optional bool rlimpulsevalid = 6;
// [km/h] [0.0|1023.0]
optional double rrimpulse = 7;
// [km/h] [0.0|1.0]
optional bool rrimpulsevalid = 8;
// [] [0.0|15.0]
optional double alivecounter = 9;
// [] [0.0|255.0]
optional double checksum = 10;
}
message Aeb_rearwheelspeed_354 {
// Report Message
// 0x0:Invalid;0x1:Valid [bit] [0.0|1.0]
optional bool wheelspeed_rl_valid = 1;
// [km/h] [0.0|327.67]
optional double wheelspeed_rl = 2;
// 0x0:Invalid;0x1:Valid [bit] [0.0|1.0]
optional bool wheelspeed_rr_valid = 3;
// [km/h] [0.0|327.67]
optional double wheelspeed_rr = 4;
// 0x0:Invalid;0x1:D;0x2:N;0x3:R [bit] [0.0|3.0]
optional double wheelspeed_rl_direct = 5;
// 0x0:Invalid;0x1:D;0x2:N;0x3:R [bit] [0.0|3.0]
optional double wheelspeed_rr_direct = 6;
// [] [0.0|15.0]
optional double alivecounter_rear = 7;
// [] [0.0|255.0]
optional double checksum_rear = 8;
}
message Aeb_frontwheelspeed_353 {
// Report Message
// 0x0:Invalid;0x1:Valid [bit] [0.0|1.0]
optional bool vehiclespeedvalid = 1;
// [Km/h] [0.0|460.69]
optional double vehiclespeed = 2;
// 0x0:Invalid;0x1:D;0x2:N;0x3:R [bit] [0.0|3.0]
optional double vehiclerealdirect = 3;
// 0x0:Invalid;0x1:Valid [bit] [0.0|1.0]
optional bool wheelspeed_fl_valid = 4;
// [km/h] [0.0|327.67]
optional double wheelspeed_fl = 5;
// 0x0:Invalid;0x1:Valid [bit] [0.0|1.0]
optional bool wheelspeed_fr_valid = 6;
// [km/h] [0.0|327.67]
optional double wheelspeed_fr = 7;
// 0x0:Invalid;0x1:D;0x2:N;0x3:R [bit] [0.0|3.0]
optional double wheelspeed_fl_direct = 8;
// 0x0:Invalid;0x1:D;0x2:N;0x3:R [bit] [0.0|3.0]
optional double wheelspeed_fr_direct = 9;
// [] [0.0|15.0]
optional double alivecounter_front = 10;
// [] [0.0|255.0]
optional double checksum_front = 11;
}
message Neolix_edu {
optional Aeb_systemstate_11 aeb_systemstate_11 = 1; // report message
optional Vcu_vehicle_fault_response_201 vcu_vehicle_fault_response_201 = 2; // report message
optional Vcu_powerstatus_214 vcu_powerstatus_214 = 3; // report message
optional Ads_light_horn_command_310 ads_light_horn_command_310 = 4; // control message
optional Ads_brake_command_46 ads_brake_command_46 = 5; // control message
optional Vcu_brake_report_47 vcu_brake_report_47 = 6; // report message
optional Vcu_eps_report_57 vcu_eps_report_57 = 7; // report message
optional Ads_eps_command_56 ads_eps_command_56 = 8; // control message
optional Ads_drive_command_50 ads_drive_command_50 = 9; // control message
optional Vcu_drive_report_52 vcu_drive_report_52 = 10; // report message
optional Ads_diagnosis_628 ads_diagnosis_628 = 11; // control message
optional Vcu_nm_401 vcu_nm_401 = 12; // report message
optional Vcu_vehicle_status_report_101 vcu_vehicle_status_report_101 = 13; // report message
optional Vcu_vehicle_info_response_502 vcu_vehicle_info_response_502 = 14; // report message
optional Aeb_diagnosis1_626 aeb_diagnosis1_626 = 15; // report message
optional Aeb_diagresp_718 aeb_diagresp_718 = 16; // report message
optional Pas_1st_data_311 pas_1st_data_311 = 17; // report message
optional Pas_2nd_data_312 pas_2nd_data_312 = 18; // report message
optional Aeb_wheelimpulse_355 aeb_wheelimpulse_355 = 19; // report message
optional Aeb_rearwheelspeed_354 aeb_rearwheelspeed_354 = 20; // report message
optional Aeb_frontwheelspeed_353 aeb_frontwheelspeed_353 = 21; // report message
}
vehicle_parameter {
brand: NEOLIX
max_enable_fail_attempt: 5
driving_mode: COMPLETE_AUTO_DRIVE
}
can_card_parameter {
brand: SOCKET_CAN_RAW
type: PCI_CARD
channel_id: CHANNEL_ID_ZERO
interface: NATIVE
}
enable_debug_mode: true
enable_receiver_log: true
enable_sender_log: true
......@@ -2,6 +2,7 @@ load("@rules_cc//cc:defs.bzl", "cc_library", "cc_test")
load("//tools:cpplint.bzl", "cpplint")
package(default_visibility = ["//visibility:public"])
CANBUS_COPTS = ["-DMODULE_NAME=\\\"canbus\\\""]
cc_library(
......@@ -49,6 +50,7 @@ cc_library(
"//modules/canbus/vehicle/gem:gem_vehicle_factory",
"//modules/canbus/vehicle/lexus:lexus_vehicle_factory",
"//modules/canbus/vehicle/lincoln:lincoln_vehicle_factory",
"//modules/canbus/vehicle/neolix_edu:neolix_edu_vehicle_factory",
"//modules/canbus/vehicle/transit:transit_vehicle_factory",
"//modules/canbus/vehicle/wey:wey_vehicle_factory",
"//modules/canbus/vehicle/zhongyun:zhongyun_vehicle_factory",
......
......@@ -2,6 +2,7 @@ load("@rules_cc//cc:defs.bzl", "cc_library", "cc_test")
load("//tools:cpplint.bzl", "cpplint")
package(default_visibility = ["//visibility:public"])
CANBUS_COPTS = ["-DMODULE_NAME=\\\"canbus\\\""]
cc_library(
......
......@@ -2,6 +2,7 @@ load("@rules_cc//cc:defs.bzl", "cc_library", "cc_test")
load("//tools:cpplint.bzl", "cpplint")
package(default_visibility = ["//visibility:public"])
CANBUS_COPTS = ["-DMODULE_NAME=\\\"canbus\\\""]
cc_library(
......
......@@ -2,6 +2,7 @@ load("@rules_cc//cc:defs.bzl", "cc_library", "cc_test")
load("//tools:cpplint.bzl", "cpplint")
package(default_visibility = ["//visibility:public"])
CANBUS_COPTS = ["-DMODULE_NAME=\\\"canbus\\\""]
cc_library(
......
......@@ -2,6 +2,7 @@ load("@rules_cc//cc:defs.bzl", "cc_library", "cc_test")
load("//tools:cpplint.bzl", "cpplint")
package(default_visibility = ["//visibility:public"])
CANBUS_COPTS = ["-DMODULE_NAME=\\\"canbus\\\""]
cc_library(
......
......@@ -2,6 +2,7 @@ load("@rules_cc//cc:defs.bzl", "cc_library", "cc_test")
load("//tools:cpplint.bzl", "cpplint")
package(default_visibility = ["//visibility:public"])
CANBUS_COPTS = ["-DMODULE_NAME=\\\"canbus\\\""]
cc_library(
......
load("@rules_cc//cc:defs.bzl", "cc_library", "cc_test")
load("//tools:cpplint.bzl", "cpplint")
package(default_visibility = ["//visibility:public"])
cc_library(
name = "neolix_edu_vehicle_factory",
srcs = [
"neolix_edu_vehicle_factory.cc",
],
hdrs = [
"neolix_edu_vehicle_factory.h",
],
deps = [
":neolix_edu_controller",
":neolix_edu_message_manager",
"//modules/canbus/vehicle:abstract_vehicle_factory",
],
)
cc_library(
name = "neolix_edu_message_manager",
srcs = [
"neolix_edu_message_manager.cc",
],
hdrs = [
"neolix_edu_message_manager.h",
],
deps = [
"//modules/canbus/proto:chassis_detail_cc_proto",
"//modules/canbus/vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol",
"//modules/drivers/canbus/can_comm:message_manager_base",
"//modules/drivers/canbus/common:canbus_common",
],
)
cc_library(
name = "neolix_edu_controller",
srcs = [
"neolix_edu_controller.cc",
],
hdrs = [
"neolix_edu_controller.h",
],
deps = [
":neolix_edu_message_manager",
"//modules/canbus/proto:chassis_detail_cc_proto",
"//modules/canbus/vehicle:vehicle_controller_base",
"//modules/canbus/vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol",
"//modules/drivers/canbus/can_comm:can_sender",
"//modules/drivers/canbus/can_comm:message_manager_base",
"//modules/drivers/canbus/common:canbus_common",
],
)
cc_test(
name = "neolix_edu_controller_test",
size = "small",
srcs = ["neolix_edu_controller_test.cc"],
data = ["//modules/canbus:canbus_testdata"],
deps = [
":neolix_edu_controller",
"@com_google_googletest//:gtest_main",
],
)
cc_test(
name = "neolix_edu_message_manager_test",
size = "small",
srcs = ["neolix_edu_message_manager_test.cc"],
deps = [
"//modules/canbus/vehicle/neolix_edu:neolix_edu_message_manager",
"@com_google_googletest//:gtest_main",
],
)
cc_test(
name = "neolix_edu_vehicle_factory_test",
size = "small",
srcs = ["neolix_edu_vehicle_factory_test.cc"],
deps = [
":neolix_edu_vehicle_factory",
"@com_google_googletest//:gtest_main",
],
)
cpplint()
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include "modules/canbus/vehicle/neolix_edu/neolix_edu_controller.h"
#include "modules/common/proto/vehicle_signal.pb.h"
#include "cyber/common/log.h"
#include "cyber/time/time.h"
#include "modules/canbus/vehicle/neolix_edu/neolix_edu_message_manager.h"
#include "modules/canbus/vehicle/vehicle_controller.h"
#include "modules/drivers/canbus/can_comm/can_sender.h"
#include "modules/drivers/canbus/can_comm/protocol_data.h"
namespace apollo {
namespace canbus {
namespace neolix_edu {
using ::apollo::common::ErrorCode;
using ::apollo::control::ControlCommand;
using ::apollo::drivers::canbus::ProtocolData;
namespace {
const int32_t kMaxFailAttempt = 10;
const int32_t CHECK_RESPONSE_STEER_UNIT_FLAG = 1;
const int32_t CHECK_RESPONSE_SPEED_UNIT_FLAG = 2;
} // namespace
ErrorCode Neolix_eduController::Init(
const VehicleParameter& params,
CanSender<::apollo::canbus::ChassisDetail>* const can_sender,
MessageManager<::apollo::canbus::ChassisDetail>* const message_manager) {
if (is_initialized_) {
AINFO << "Neolix_eduController has already been initiated.";
return ErrorCode::CANBUS_ERROR;
}
vehicle_params_.CopyFrom(
common::VehicleConfigHelper::Instance()->GetConfig().vehicle_param());
params_.CopyFrom(params);
if (!params_.has_driving_mode()) {
AERROR << "Vehicle conf pb not set driving_mode.";
return ErrorCode::CANBUS_ERROR;
}
if (can_sender == nullptr) {
return ErrorCode::CANBUS_ERROR;
}
can_sender_ = can_sender;
if (message_manager == nullptr) {
AERROR << "protocol manager is null.";
return ErrorCode::CANBUS_ERROR;
}
message_manager_ = message_manager;
// sender part
ads_brake_command_46_ = dynamic_cast<Adsbrakecommand46*>(
message_manager_->GetMutableProtocolDataById(Adsbrakecommand46::ID));
if (ads_brake_command_46_ == nullptr) {
AERROR
<< "Adsbrakecommand46 does not exist in the Neolix_eduMessageManager!";
return ErrorCode::CANBUS_ERROR;
}
ads_diagnosis_628_ = dynamic_cast<Adsdiagnosis628*>(
message_manager_->GetMutableProtocolDataById(Adsdiagnosis628::ID));
if (ads_diagnosis_628_ == nullptr) {
AERROR << "Adsdiagnosis628 does not exist in the Neolix_eduMessageManager!";
return ErrorCode::CANBUS_ERROR;
}
ads_drive_command_50_ = dynamic_cast<Adsdrivecommand50*>(
message_manager_->GetMutableProtocolDataById(Adsdrivecommand50::ID));
if (ads_drive_command_50_ == nullptr) {
AERROR
<< "Adsdrivecommand50 does not exist in the Neolix_eduMessageManager!";
return ErrorCode::CANBUS_ERROR;
}
ads_eps_command_56_ = dynamic_cast<Adsepscommand56*>(
message_manager_->GetMutableProtocolDataById(Adsepscommand56::ID));
if (ads_eps_command_56_ == nullptr) {
AERROR << "Adsepscommand56 does not exist in the Neolix_eduMessageManager!";
return ErrorCode::CANBUS_ERROR;
}
ads_light_horn_command_310_ = dynamic_cast<Adslighthorncommand310*>(
message_manager_->GetMutableProtocolDataById(Adslighthorncommand310::ID));
if (ads_light_horn_command_310_ == nullptr) {
AERROR << "Adslighthorncommand310 does not exist in the "
"Neolix_eduMessageManager!";
return ErrorCode::CANBUS_ERROR;
}
can_sender_->AddMessage(Adsbrakecommand46::ID, ads_brake_command_46_, false);
can_sender_->AddMessage(Adsdiagnosis628::ID, ads_diagnosis_628_, false);
can_sender_->AddMessage(Adsdrivecommand50::ID, ads_drive_command_50_, false);
can_sender_->AddMessage(Adsepscommand56::ID, ads_eps_command_56_, false);
can_sender_->AddMessage(Adslighthorncommand310::ID,
ads_light_horn_command_310_, false);
// need sleep to ensure all messages received
AINFO << "Neolix_eduController is initialized.";
is_initialized_ = true;
return ErrorCode::OK;
}
Neolix_eduController::~Neolix_eduController() {}
bool Neolix_eduController::Start() {
if (!is_initialized_) {
AERROR << "Neolix_eduController has NOT been initiated.";
return false;
}
const auto& update_func = [this] { SecurityDogThreadFunc(); };
thread_.reset(new std::thread(update_func));
return true;
}
void Neolix_eduController::Stop() {
if (!is_initialized_) {
AERROR << "Neolix_eduController stops or starts improperly!";
return;
}
if (thread_ != nullptr && thread_->joinable()) {
thread_->join();
thread_.reset();
AINFO << "Neolix_eduController stopped.";
}
}
Chassis Neolix_eduController::chassis() {
chassis_.Clear();
ChassisDetail chassis_detail;
message_manager_->GetSensorData(&chassis_detail);
// 21, 22, previously 1, 2
if (driving_mode() == Chassis::EMERGENCY_MODE) {
set_chassis_error_code(Chassis::NO_ERROR);
}
chassis_.set_driving_mode(driving_mode());
chassis_.set_error_code(chassis_error_code());
// 3
chassis_.set_engine_started(true);
// 4 speed_mps
if (chassis_detail.neolix_edu().has_aeb_frontwheelspeed_353() &&
chassis_detail.neolix_edu().has_aeb_rearwheelspeed_354()) {
auto wheelspeed = chassis_.mutable_wheel_speed();
wheelspeed->set_wheel_spd_fl(
chassis_detail.neolix_edu().aeb_frontwheelspeed_353().wheelspeed_fl());
wheelspeed->set_wheel_spd_fr(
chassis_detail.neolix_edu().aeb_frontwheelspeed_353().wheelspeed_fr());
wheelspeed->set_wheel_spd_rl(
chassis_detail.neolix_edu().aeb_rearwheelspeed_354().wheelspeed_rl());
wheelspeed->set_wheel_spd_rr(
chassis_detail.neolix_edu().aeb_rearwheelspeed_354().wheelspeed_rr());
chassis_.set_speed_mps(
(chassis_detail.neolix_edu().aeb_frontwheelspeed_353().wheelspeed_fl() +
chassis_detail.neolix_edu().aeb_frontwheelspeed_353().wheelspeed_fr() +
chassis_detail.neolix_edu().aeb_rearwheelspeed_354().wheelspeed_rl() +
chassis_detail.neolix_edu().aeb_rearwheelspeed_354().wheelspeed_rr()) /
4 / 3.6);
} else {
chassis_.set_speed_mps(0);
}
// 5 steering
if (chassis_detail.neolix_edu().has_vcu_eps_report_57() &&
chassis_detail.neolix_edu().vcu_eps_report_57().has_vcu_real_angle()) {
chassis_.set_steering_percentage(static_cast<float>(
chassis_detail.neolix_edu().vcu_eps_report_57().vcu_real_angle() * 100 /
vehicle_params_.max_steer_angle() * M_PI / 180));
} else {
chassis_.set_steering_percentage(0);
}
// 6 throttle
if (chassis_detail.neolix_edu().has_vcu_drive_report_52() &&
chassis_detail.neolix_edu().vcu_drive_report_52().has_vcu_real_torque()) {
chassis_.set_throttle_percentage(
chassis_detail.neolix_edu().vcu_drive_report_52().vcu_real_torque() *
2);
} else {
chassis_.set_throttle_percentage(0);
}
// 7 brake
if (chassis_detail.neolix_edu().has_vcu_brake_report_47() &&
chassis_detail.neolix_edu().vcu_brake_report_47().has_vcu_real_brake()) {
chassis_.set_brake_percentage(
chassis_detail.neolix_edu().vcu_brake_report_47().vcu_real_brake());
} else {
chassis_.set_brake_percentage(0);
}
// 8 gear
if (chassis_detail.neolix_edu().has_vcu_drive_report_52() &&
chassis_detail.neolix_edu().vcu_drive_report_52().has_vcu_real_shift()) {
chassis_.set_gear_location(
(apollo::canbus::Chassis_GearPosition)chassis_detail.neolix_edu()
.vcu_drive_report_52()
.vcu_real_shift());
}
// 9 epb
if (chassis_detail.neolix_edu().has_vcu_brake_report_47() &&
chassis_detail.neolix_edu()
.vcu_brake_report_47()
.has_vcu_real_parking_status()) {
if (chassis_detail.neolix_edu()
.vcu_brake_report_47()
.vcu_real_parking_status() == 1) {
chassis_.set_parking_brake(true);
} else {
chassis_.set_parking_brake(false);
}
} else {
chassis_.set_parking_brake(false);
}
if (chassis_error_mask_) {
chassis_.set_chassis_error_mask(chassis_error_mask_);
}
// give engage_advice based on error_code and canbus feedback
if (!chassis_error_mask_ && !chassis_.parking_brake() &&
(chassis_.throttle_percentage() == 0.0)) {
chassis_.mutable_engage_advice()->set_advice(
apollo::common::EngageAdvice::READY_TO_ENGAGE);
} else {
chassis_.mutable_engage_advice()->set_advice(
apollo::common::EngageAdvice::DISALLOW_ENGAGE);
chassis_.mutable_engage_advice()->set_reason(
"CANBUS not ready, firmware error or emergency button pressed!");
}
return chassis_;
}
void Neolix_eduController::Emergency() {
set_driving_mode(Chassis::EMERGENCY_MODE);
ResetProtocol();
}
ErrorCode Neolix_eduController::EnableAutoMode() {
if (driving_mode() == Chassis::COMPLETE_AUTO_DRIVE) {
AINFO << "already in COMPLETE_AUTO_DRIVE mode";
return ErrorCode::OK;
}
// set enable
ads_brake_command_46_->set_drive_enable(true);
ads_drive_command_50_->set_drive_enable(true);
ads_eps_command_56_->set_drive_enable(true);
can_sender_->Update();
const int32_t flag =
CHECK_RESPONSE_STEER_UNIT_FLAG | CHECK_RESPONSE_SPEED_UNIT_FLAG;
if (!CheckResponse(flag, true)) {
AERROR << "Failed to switch to COMPLETE_AUTO_DRIVE mode.";
Emergency();
set_chassis_error_code(Chassis::CHASSIS_ERROR);
return ErrorCode::CANBUS_ERROR;
}
set_driving_mode(Chassis::COMPLETE_AUTO_DRIVE);
AINFO << "Switch to COMPLETE_AUTO_DRIVE mode ok.";
return ErrorCode::OK;
}
ErrorCode Neolix_eduController::DisableAutoMode() {
ResetProtocol();
can_sender_->Update();
set_driving_mode(Chassis::COMPLETE_MANUAL);
set_chassis_error_code(Chassis::NO_ERROR);
AINFO << "Switch to COMPLETE_MANUAL ok.";
return ErrorCode::OK;
}
ErrorCode Neolix_eduController::EnableSteeringOnlyMode() {
if (driving_mode() == Chassis::COMPLETE_AUTO_DRIVE ||
driving_mode() == Chassis::AUTO_STEER_ONLY) {
set_driving_mode(Chassis::AUTO_STEER_ONLY);
AINFO << "Already in AUTO_STEER_ONLY mode.";
return ErrorCode::OK;
}
AFATAL << "SpeedOnlyMode is not supported in Neolix_edu!";
return ErrorCode::OK;
}
ErrorCode Neolix_eduController::EnableSpeedOnlyMode() {
if (driving_mode() == Chassis::COMPLETE_AUTO_DRIVE ||
driving_mode() == Chassis::AUTO_SPEED_ONLY) {
set_driving_mode(Chassis::AUTO_SPEED_ONLY);
AINFO << "Already in AUTO_SPEED_ONLY mode";
return ErrorCode::OK;
}
AFATAL << "SpeedOnlyMode is not supported in Neolix_edu!";
return ErrorCode::OK;
}
// NEUTRAL, REVERSE, DRIVE
void Neolix_eduController::Gear(Chassis::GearPosition gear_position) {
if (driving_mode() != Chassis::COMPLETE_AUTO_DRIVE &&
driving_mode() != Chassis::AUTO_SPEED_ONLY) {
AINFO << "This drive mode no need to set gear.";
return;
}
switch (gear_position) {
case Chassis::GEAR_NEUTRAL: {
ads_drive_command_50_->set_auto_shift_command(
Ads_drive_command_50::AUTO_SHIFT_COMMAND_N);
ads_brake_command_46_->set_auto_parking_command(false);
break;
}
case Chassis::GEAR_REVERSE: {
ads_drive_command_50_->set_auto_shift_command(
Ads_drive_command_50::AUTO_SHIFT_COMMAND_R);
break;
}
case Chassis::GEAR_DRIVE: {
ads_drive_command_50_->set_auto_shift_command(
Ads_drive_command_50::AUTO_SHIFT_COMMAND_D);
break;
}
case Chassis::GEAR_PARKING: {
ads_brake_command_46_->set_auto_parking_command(true);
break;
}
default:
break;
}
}
// brake with pedal
// pedal:0.00~99.99, unit:
void Neolix_eduController::Brake(double pedal) {
// TODO(All) : Update brake value based on mode
if (driving_mode() != Chassis::COMPLETE_AUTO_DRIVE &&
driving_mode() != Chassis::AUTO_SPEED_ONLY) {
AINFO << "The current drive mode does not need to set brake pedal.";
return;
}
ads_brake_command_46_->set_auto_brake_command(pedal);
}
// drive with old acceleration
// gas:0.00~99.99 unit:
void Neolix_eduController::Throttle(double pedal) {
if (driving_mode() != Chassis::COMPLETE_AUTO_DRIVE &&
driving_mode() != Chassis::AUTO_SPEED_ONLY) {
AINFO << "The current drive mode does not need to set throttle pedal.";
return;
}
ads_drive_command_50_->set_auto_drive_torque(pedal / 2);
}
// confirm the car is driven by acceleration command or throttle/brake pedal
// drive with acceleration/deceleration
// acc:-7.0 ~ 5.0, unit:m/s^2
void Neolix_eduController::Acceleration(double acc) {
// None
}
// neolix_edu default, -380 ~ 380, left:+, right:-
// need to be compatible with control module, so reverse
// steering with old angle speed
// angle:-99.99~0.00~99.99, unit:, left:-, right:+
void Neolix_eduController::Steer(double angle) {
if (driving_mode() != Chassis::COMPLETE_AUTO_DRIVE &&
driving_mode() != Chassis::AUTO_STEER_ONLY) {
AINFO << "The current driving mode does not need to set steer.";
return;
}
const double real_angle =
vehicle_params_.max_steer_angle() / M_PI * 180 * angle / 100.0;
ads_eps_command_56_->set_auto_target_angle(real_angle);
}
// steering with new angle speed
// angle:-99.99~0.00~99.99, unit:, left:-, right:+
// angle_spd:0.00~99.99, unit:deg/s
void Neolix_eduController::Steer(double angle, double angle_spd) {
if (driving_mode() != Chassis::COMPLETE_AUTO_DRIVE &&
driving_mode() != Chassis::AUTO_STEER_ONLY) {
AINFO << "The current driving mode does not need to set steer.";
return;
}
const double real_angle =
vehicle_params_.max_steer_angle() / M_PI * 180 * angle / 100.0;
ads_eps_command_56_->set_auto_target_angle(real_angle);
}
void Neolix_eduController::SetEpbBreak(const ControlCommand& command) {
if (command.parking_brake()) {
ads_brake_command_46_->set_auto_parking_command(true);
} else {
ads_brake_command_46_->set_auto_parking_command(false);
}
}
void Neolix_eduController::SetBeam(const ControlCommand& command) {
if (command.signal().high_beam()) {
// None
} else if (command.signal().low_beam()) {
// None
} else {
// None
}
}
void Neolix_eduController::SetHorn(const ControlCommand& command) {
if (command.signal().horn()) {
// None
} else {
// None
}
}
void Neolix_eduController::SetTurningSignal(const ControlCommand& command) {
// None
}
void Neolix_eduController::ResetProtocol() {
message_manager_->ResetSendMessages();
}
bool Neolix_eduController::CheckChassisError() {
/* ADD YOUR OWN CAR CHASSIS OPERATION
*/
return false;
}
void Neolix_eduController::SecurityDogThreadFunc() {
int32_t vertical_ctrl_fail = 0;
int32_t horizontal_ctrl_fail = 0;
if (can_sender_ == nullptr) {
AERROR << "Failed to run SecurityDogThreadFunc() because can_sender_ is "
"nullptr.";
return;
}
while (!can_sender_->IsRunning()) {
std::this_thread::yield();
}
std::chrono::duration<double, std::micro> default_period{50000};
int64_t start = 0;
int64_t end = 0;
while (can_sender_->IsRunning()) {
start = ::apollo::cyber::Time::Now().ToMicrosecond();
const Chassis::DrivingMode mode = driving_mode();
bool emergency_mode = false;
// 1. horizontal control check
if ((mode == Chassis::COMPLETE_AUTO_DRIVE ||
mode == Chassis::AUTO_STEER_ONLY) &&
CheckResponse(CHECK_RESPONSE_STEER_UNIT_FLAG, false) == false) {
++horizontal_ctrl_fail;
if (horizontal_ctrl_fail >= kMaxFailAttempt) {
emergency_mode = true;
set_chassis_error_code(Chassis::MANUAL_INTERVENTION);
}
} else {
horizontal_ctrl_fail = 0;
}
// 2. vertical control check
if ((mode == Chassis::COMPLETE_AUTO_DRIVE ||
mode == Chassis::AUTO_SPEED_ONLY) &&
!CheckResponse(CHECK_RESPONSE_SPEED_UNIT_FLAG, false)) {
++vertical_ctrl_fail;
if (vertical_ctrl_fail >= kMaxFailAttempt) {
emergency_mode = true;
set_chassis_error_code(Chassis::MANUAL_INTERVENTION);
}
} else {
vertical_ctrl_fail = 0;
}
if (CheckChassisError()) {
set_chassis_error_code(Chassis::CHASSIS_ERROR);
emergency_mode = true;
}
if (emergency_mode && mode != Chassis::EMERGENCY_MODE) {
set_driving_mode(Chassis::EMERGENCY_MODE);
message_manager_->ResetSendMessages();
}
end = ::apollo::cyber::Time::Now().ToMicrosecond();
std::chrono::duration<double, std::micro> elapsed{end - start};
if (elapsed < default_period) {
std::this_thread::sleep_for(default_period - elapsed);
} else {
AERROR << "Too much time consumption in Neolix_eduController looping "
"process:"
<< elapsed.count();
}
}
}
bool Neolix_eduController::CheckResponse(const int32_t flags, bool need_wait) {
int32_t retry_num = 20;
ChassisDetail chassis_detail;
bool is_eps_online = false;
bool is_vcu_online = false;
bool is_esp_online = false;
do {
if (message_manager_->GetSensorData(&chassis_detail) != ErrorCode::OK) {
AERROR_EVERY(100) << "get chassis detail failed.";
return false;
}
bool check_ok = true;
if (flags & CHECK_RESPONSE_STEER_UNIT_FLAG) {
is_eps_online = chassis_detail.has_check_response() &&
chassis_detail.check_response().has_is_eps_online() &&
chassis_detail.check_response().is_eps_online();
check_ok = check_ok && is_eps_online;
}
if (flags & CHECK_RESPONSE_SPEED_UNIT_FLAG) {
is_vcu_online = chassis_detail.has_check_response() &&
chassis_detail.check_response().has_is_vcu_online() &&
chassis_detail.check_response().is_vcu_online();
is_esp_online = chassis_detail.has_check_response() &&
chassis_detail.check_response().has_is_esp_online() &&
chassis_detail.check_response().is_esp_online();
check_ok = check_ok && is_vcu_online && is_esp_online;
}
if (check_ok) {
return true;
} else {
AINFO << "Need to check response again.";
}
if (need_wait) {
--retry_num;
std::this_thread::sleep_for(
std::chrono::duration<double, std::milli>(20));
}
} while (need_wait && retry_num);
AINFO << "check_response fail: is_eps_online:" << is_eps_online
<< ", is_vcu_online:" << is_vcu_online
<< ", is_esp_online:" << is_esp_online;
return false;
}
void Neolix_eduController::set_chassis_error_mask(const int32_t mask) {
std::lock_guard<std::mutex> lock(chassis_mask_mutex_);
chassis_error_mask_ = mask;
}
int32_t Neolix_eduController::chassis_error_mask() {
std::lock_guard<std::mutex> lock(chassis_mask_mutex_);
return chassis_error_mask_;
}
Chassis::ErrorCode Neolix_eduController::chassis_error_code() {
std::lock_guard<std::mutex> lock(chassis_error_code_mutex_);
return chassis_error_code_;
}
void Neolix_eduController::set_chassis_error_code(
const Chassis::ErrorCode& error_code) {
std::lock_guard<std::mutex> lock(chassis_error_code_mutex_);
chassis_error_code_ = error_code;
}
} // namespace neolix_edu
} // namespace canbus
} // namespace apollo
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#pragma once
#include <memory>
#include <thread>
#include "modules/canbus/vehicle/vehicle_controller.h"
#include "modules/canbus/proto/canbus_conf.pb.h"
#include "modules/canbus/proto/chassis.pb.h"
#include "modules/canbus/proto/vehicle_parameter.pb.h"
#include "modules/common/proto/error_code.pb.h"
#include "modules/control/proto/control_cmd.pb.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/ads_brake_command_46.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/ads_diagnosis_628.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/ads_drive_command_50.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/ads_eps_command_56.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/ads_light_horn_command_310.h"
namespace apollo {
namespace canbus {
namespace neolix_edu {
class Neolix_eduController final : public VehicleController {
public:
virtual ~Neolix_eduController();
::apollo::common::ErrorCode Init(
const VehicleParameter& params,
CanSender<::apollo::canbus::ChassisDetail>* const can_sender,
MessageManager<::apollo::canbus::ChassisDetail>* const message_manager)
override;
bool Start() override;
/**
* @brief stop the vehicle controller.
*/
void Stop() override;
/**
* @brief calculate and return the chassis.
* @returns a copy of chassis. Use copy here to avoid multi-thread issues.
*/
Chassis chassis() override;
FRIEND_TEST(Neolix_eduControllerTest, SetDrivingMode);
FRIEND_TEST(Neolix_eduControllerTest, Status);
FRIEND_TEST(Neolix_eduControllerTest, UpdateDrivingMode);
private:
// main logical function for operation the car enter or exit the auto driving
void Emergency() override;
::apollo::common::ErrorCode EnableAutoMode() override;
::apollo::common::ErrorCode DisableAutoMode() override;
::apollo::common::ErrorCode EnableSteeringOnlyMode() override;
::apollo::common::ErrorCode EnableSpeedOnlyMode() override;
// NEUTRAL, REVERSE, DRIVE
void Gear(Chassis::GearPosition state) override;
// brake with new acceleration
// acceleration:0.00~99.99, unit:
// acceleration_spd: 60 ~ 100, suggest: 90
void Brake(double acceleration) override;
// drive with old acceleration
// gas:0.00~99.99 unit:
void Throttle(double throttle) override;
// drive with acceleration/deceleration
// acc:-7.0~5.0 unit:m/s^2
void Acceleration(double acc) override;
// steering with old angle speed
// angle:-99.99~0.00~99.99, unit:, left:+, right:-
void Steer(double angle) override;
// steering with new angle speed
// angle:-99.99~0.00~99.99, unit:, left:+, right:-
// angle_spd:0.00~99.99, unit:deg/s
void Steer(double angle, double angle_spd) override;
// set Electrical Park Brake
void SetEpbBreak(const ::apollo::control::ControlCommand& command) override;
void SetBeam(const ::apollo::control::ControlCommand& command) override;
void SetHorn(const ::apollo::control::ControlCommand& command) override;
void SetTurningSignal(
const ::apollo::control::ControlCommand& command) override;
void ResetProtocol();
bool CheckChassisError();
private:
void SecurityDogThreadFunc();
virtual bool CheckResponse(const int32_t flags, bool need_wait);
void set_chassis_error_mask(const int32_t mask);
int32_t chassis_error_mask();
Chassis::ErrorCode chassis_error_code();
void set_chassis_error_code(const Chassis::ErrorCode& error_code);
private:
// control protocol
Adsbrakecommand46* ads_brake_command_46_ = nullptr;
Adsdiagnosis628* ads_diagnosis_628_ = nullptr;
Adsdrivecommand50* ads_drive_command_50_ = nullptr;
Adsepscommand56* ads_eps_command_56_ = nullptr;
Adslighthorncommand310* ads_light_horn_command_310_ = nullptr;
Chassis chassis_;
std::unique_ptr<std::thread> thread_;
bool is_chassis_error_ = false;
std::mutex chassis_error_code_mutex_;
Chassis::ErrorCode chassis_error_code_ = Chassis::NO_ERROR;
std::mutex chassis_mask_mutex_;
int32_t chassis_error_mask_ = 0;
};
} // namespace neolix_edu
} // namespace canbus
} // namespace apollo
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or
*implied. See the License for the specific language governing permissions
*and limitations under the License.
*****************************************************************************/
#include "modules/canbus/vehicle/neolix_edu/neolix_edu_controller.h"
#include "cyber/common/file.h"
#include "gtest/gtest.h"
#include "modules/canbus/proto/canbus_conf.pb.h"
#include "modules/canbus/proto/chassis.pb.h"
#include "modules/canbus/proto/chassis_detail.pb.h"
#include "modules/canbus/vehicle/neolix_edu/neolix_edu_message_manager.h"
#include "modules/common/proto/vehicle_signal.pb.h"
#include "modules/control/proto/control_cmd.pb.h"
#include "modules/drivers/canbus/can_comm/can_sender.h"
namespace apollo {
namespace canbus {
namespace neolix_edu {
using apollo::common::ErrorCode;
using apollo::common::VehicleSignal;
using apollo::control::ControlCommand;
class Neolix_eduControllerTest : public ::testing::Test {
public:
virtual void SetUp() {
std::string canbus_conf_file =
"/apollo/modules/canbus/testdata/conf/"
"neolix_edu_canbus_conf_test.pb.txt";
cyber::common::GetProtoFromFile(canbus_conf_file, &canbus_conf_);
params_ = canbus_conf_.vehicle_parameter();
control_cmd_.set_throttle(20.0);
control_cmd_.set_brake(0.0);
control_cmd_.set_steering_rate(80.0);
control_cmd_.set_horn(false);
}
protected:
Neolix_eduController controller_;
ControlCommand control_cmd_;
VehicleSignal vehicle_signal_;
CanSender<::apollo::canbus::ChassisDetail> sender_;
Neolix_eduMessageManager msg_manager_;
CanbusConf canbus_conf_;
VehicleParameter params_;
};
TEST_F(Neolix_eduControllerTest, Init) {
ErrorCode ret = controller_.Init(params_, &sender_, &msg_manager_);
EXPECT_EQ(ret, ErrorCode::OK);
}
TEST_F(Neolix_eduControllerTest, SetDrivingMode) {
Chassis chassis;
chassis.set_driving_mode(Chassis::COMPLETE_AUTO_DRIVE);
controller_.Init(params_, &sender_, &msg_manager_);
controller_.set_driving_mode(chassis.driving_mode());
EXPECT_EQ(controller_.driving_mode(), chassis.driving_mode());
EXPECT_EQ(controller_.SetDrivingMode(chassis.driving_mode()), ErrorCode::OK);
}
TEST_F(Neolix_eduControllerTest, Status) {
controller_.Init(params_, &sender_, &msg_manager_);
controller_.set_driving_mode(Chassis::COMPLETE_AUTO_DRIVE);
EXPECT_EQ(controller_.Update(control_cmd_), ErrorCode::OK);
controller_.SetHorn(control_cmd_);
controller_.SetBeam(control_cmd_);
controller_.SetTurningSignal(control_cmd_);
EXPECT_FALSE(controller_.CheckChassisError());
EXPECT_EQ(controller_.chassis_error_code(), Chassis::NO_ERROR);
}
TEST_F(Neolix_eduControllerTest, UpdateDrivingMode) {
controller_.Init(params_, &sender_, &msg_manager_);
controller_.set_driving_mode(Chassis::COMPLETE_AUTO_DRIVE);
EXPECT_EQ(controller_.SetDrivingMode(Chassis::COMPLETE_MANUAL),
ErrorCode::OK);
controller_.set_driving_mode(Chassis::COMPLETE_AUTO_DRIVE);
EXPECT_EQ(controller_.SetDrivingMode(Chassis::AUTO_STEER_ONLY),
ErrorCode::OK);
controller_.set_driving_mode(Chassis::COMPLETE_AUTO_DRIVE);
EXPECT_EQ(controller_.SetDrivingMode(Chassis::AUTO_SPEED_ONLY),
ErrorCode::OK);
EXPECT_EQ(controller_.SetDrivingMode(Chassis::COMPLETE_AUTO_DRIVE),
ErrorCode::CANBUS_ERROR);
}
} // namespace neolix_edu
} // namespace canbus
} // namespace apollo
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include "modules/canbus/vehicle/neolix_edu/neolix_edu_message_manager.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/ads_brake_command_46.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/ads_diagnosis_628.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/ads_drive_command_50.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/ads_eps_command_56.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/ads_light_horn_command_310.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_diagnosis1_626.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_diagresp_718.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_frontwheelspeed_353.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_rearwheelspeed_354.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_systemstate_11.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_wheelimpulse_355.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/pas_1st_data_311.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/pas_2nd_data_312.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_brake_report_47.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_drive_report_52.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_eps_report_57.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_nm_401.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_powerstatus_214.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_fault_response_201.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_info_response_502.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_status_report_101.h"
namespace apollo {
namespace canbus {
namespace neolix_edu {
Neolix_eduMessageManager::Neolix_eduMessageManager() {
// Control Messages
AddSendProtocolData<Adsbrakecommand46, true>();
AddSendProtocolData<Adsdiagnosis628, true>();
AddSendProtocolData<Adsdrivecommand50, true>();
AddSendProtocolData<Adsepscommand56, true>();
AddSendProtocolData<Adslighthorncommand310, true>();
// Report Messages
AddRecvProtocolData<Aebsystemstate11, true>();
AddRecvProtocolData<Vcubrakereport47, true>();
AddRecvProtocolData<Vcudrivereport52, true>();
AddRecvProtocolData<Vcuepsreport57, true>();
AddRecvProtocolData<Vcunm401, true>();
AddRecvProtocolData<Vcupowerstatus214, true>();
AddRecvProtocolData<Vcuvehiclefaultresponse201, true>();
AddRecvProtocolData<Vcuvehicleinforesponse502, true>();
AddRecvProtocolData<Vcuvehiclestatusreport101, true>();
AddRecvProtocolData<Aebdiagnosis1626, true>();
AddRecvProtocolData<Aebdiagresp718, true>();
AddRecvProtocolData<Aebfrontwheelspeed353, true>();
AddRecvProtocolData<Aebrearwheelspeed354, true>();
AddRecvProtocolData<Aebwheelimpulse355, true>();
AddRecvProtocolData<Pas1stdata311, true>();
AddRecvProtocolData<Pas2nddata312, true>();
}
Neolix_eduMessageManager::~Neolix_eduMessageManager() {}
} // namespace neolix_edu
} // namespace canbus
} // namespace apollo
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#pragma once
#include "modules/canbus/proto/chassis_detail.pb.h"
#include "modules/drivers/canbus/can_comm/message_manager.h"
namespace apollo {
namespace canbus {
namespace neolix_edu {
using ::apollo::drivers::canbus::MessageManager;
class Neolix_eduMessageManager
: public MessageManager<::apollo::canbus::ChassisDetail> {
public:
Neolix_eduMessageManager();
virtual ~Neolix_eduMessageManager();
};
} // namespace neolix_edu
} // namespace canbus
} // namespace apollo
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include "modules/canbus/vehicle/neolix_edu/neolix_edu_message_manager.h"
#include "gtest/gtest.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/ads_brake_command_46.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/ads_diagnosis_628.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/ads_drive_command_50.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/ads_eps_command_56.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/ads_light_horn_command_310.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_diagnosis1_626.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_diagresp_718.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_frontwheelspeed_353.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_rearwheelspeed_354.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_systemstate_11.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_wheelimpulse_355.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/pas_1st_data_311.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/pas_2nd_data_312.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_brake_report_47.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_drive_report_52.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_eps_report_57.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_nm_401.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_powerstatus_214.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_fault_response_201.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_info_response_502.h"
#include "modules/canbus/vehicle/neolix_edu/protocol/vcu_vehicle_status_report_101.h"
namespace apollo {
namespace canbus {
namespace neolix_edu {
using ::apollo::canbus::ChassisDetail;
using ::apollo::drivers::canbus::ProtocolData;
class Neolix_eduMessageManagerTest : public ::testing::Test {
public:
virtual void SetUp() {}
};
// Control Messages
TEST_F(Neolix_eduMessageManagerTest, Adsbrakecommand46) {
Neolix_eduMessageManager manager;
ProtocolData<ChassisDetail> *pd =
manager.GetMutableProtocolDataById(Adsbrakecommand46::ID);
EXPECT_NE(pd, nullptr);
EXPECT_EQ(static_cast<Adsbrakecommand46 *>(pd)->ID, Adsbrakecommand46::ID);
}
TEST_F(Neolix_eduMessageManagerTest, Adsdiagnosis628) {
Neolix_eduMessageManager manager;
ProtocolData<ChassisDetail> *pd =
manager.GetMutableProtocolDataById(Adsdiagnosis628::ID);
EXPECT_NE(pd, nullptr);
EXPECT_EQ(static_cast<Adsdiagnosis628 *>(pd)->ID, Adsdiagnosis628::ID);
}
TEST_F(Neolix_eduMessageManagerTest, Adsdrivecommand50) {
Neolix_eduMessageManager manager;
ProtocolData<ChassisDetail> *pd =
manager.GetMutableProtocolDataById(Adsdrivecommand50::ID);
EXPECT_NE(pd, nullptr);
EXPECT_EQ(static_cast<Adsdrivecommand50 *>(pd)->ID, Adsdrivecommand50::ID);
}
TEST_F(Neolix_eduMessageManagerTest, Adsepscommand56) {
Neolix_eduMessageManager manager;
ProtocolData<ChassisDetail> *pd =
manager.GetMutableProtocolDataById(Adsepscommand56::ID);
EXPECT_NE(pd, nullptr);
EXPECT_EQ(static_cast<Adsepscommand56 *>(pd)->ID, Adsepscommand56::ID);
}
TEST_F(Neolix_eduMessageManagerTest, Adslighthorncommand310) {
Neolix_eduMessageManager manager;
ProtocolData<ChassisDetail> *pd =
manager.GetMutableProtocolDataById(Adslighthorncommand310::ID);
EXPECT_NE(pd, nullptr);
EXPECT_EQ(static_cast<Adslighthorncommand310 *>(pd)->ID,
Adslighthorncommand310::ID);
}
// Report Messages
TEST_F(Neolix_eduMessageManagerTest, Aebsystemstate11) {
Neolix_eduMessageManager manager;
ProtocolData<ChassisDetail> *pd =
manager.GetMutableProtocolDataById(Aebsystemstate11::ID);
EXPECT_NE(pd, nullptr);
EXPECT_EQ(static_cast<Aebsystemstate11 *>(pd)->ID, Aebsystemstate11::ID);
}
TEST_F(Neolix_eduMessageManagerTest, Vcubrakereport47) {
Neolix_eduMessageManager manager;
ProtocolData<ChassisDetail> *pd =
manager.GetMutableProtocolDataById(Vcubrakereport47::ID);
EXPECT_NE(pd, nullptr);
EXPECT_EQ(static_cast<Vcubrakereport47 *>(pd)->ID, Vcubrakereport47::ID);
}
TEST_F(Neolix_eduMessageManagerTest, Vcudrivereport52) {
Neolix_eduMessageManager manager;
ProtocolData<ChassisDetail> *pd =
manager.GetMutableProtocolDataById(Vcudrivereport52::ID);
EXPECT_NE(pd, nullptr);
EXPECT_EQ(static_cast<Vcudrivereport52 *>(pd)->ID, Vcudrivereport52::ID);
}
TEST_F(Neolix_eduMessageManagerTest, Vcuepsreport57) {
Neolix_eduMessageManager manager;
ProtocolData<ChassisDetail> *pd =
manager.GetMutableProtocolDataById(Vcuepsreport57::ID);
EXPECT_NE(pd, nullptr);
EXPECT_EQ(static_cast<Vcuepsreport57 *>(pd)->ID, Vcuepsreport57::ID);
}
TEST_F(Neolix_eduMessageManagerTest, Vcunm401) {
Neolix_eduMessageManager manager;
ProtocolData<ChassisDetail> *pd =
manager.GetMutableProtocolDataById(Vcunm401::ID);
EXPECT_NE(pd, nullptr);
EXPECT_EQ(static_cast<Vcunm401 *>(pd)->ID, Vcunm401::ID);
}
TEST_F(Neolix_eduMessageManagerTest, Vcupowerstatus214) {
Neolix_eduMessageManager manager;
ProtocolData<ChassisDetail> *pd =
manager.GetMutableProtocolDataById(Vcupowerstatus214::ID);
EXPECT_NE(pd, nullptr);
EXPECT_EQ(static_cast<Vcupowerstatus214 *>(pd)->ID, Vcupowerstatus214::ID);
}
TEST_F(Neolix_eduMessageManagerTest, Vcuvehiclefaultresponse201) {
Neolix_eduMessageManager manager;
ProtocolData<ChassisDetail> *pd =
manager.GetMutableProtocolDataById(Vcuvehiclefaultresponse201::ID);
EXPECT_NE(pd, nullptr);
EXPECT_EQ(static_cast<Vcuvehiclefaultresponse201 *>(pd)->ID,
Vcuvehiclefaultresponse201::ID);
}
TEST_F(Neolix_eduMessageManagerTest, Vcuvehicleinforesponse502) {
Neolix_eduMessageManager manager;
ProtocolData<ChassisDetail> *pd =
manager.GetMutableProtocolDataById(Vcuvehicleinforesponse502::ID);
EXPECT_NE(pd, nullptr);
EXPECT_EQ(static_cast<Vcuvehicleinforesponse502 *>(pd)->ID,
Vcuvehicleinforesponse502::ID);
}
TEST_F(Neolix_eduMessageManagerTest, Vcuvehiclestatusreport101) {
Neolix_eduMessageManager manager;
ProtocolData<ChassisDetail> *pd =
manager.GetMutableProtocolDataById(Vcuvehiclestatusreport101::ID);
EXPECT_NE(pd, nullptr);
EXPECT_EQ(static_cast<Vcuvehiclestatusreport101 *>(pd)->ID,
Vcuvehiclestatusreport101::ID);
}
TEST_F(Neolix_eduMessageManagerTest, Aebdiagnosis1626) {
Neolix_eduMessageManager manager;
ProtocolData<ChassisDetail> *pd =
manager.GetMutableProtocolDataById(Aebdiagnosis1626::ID);
EXPECT_NE(pd, nullptr);
EXPECT_EQ(static_cast<Aebdiagnosis1626 *>(pd)->ID, Aebdiagnosis1626::ID);
}
TEST_F(Neolix_eduMessageManagerTest, Aebdiagresp718) {
Neolix_eduMessageManager manager;
ProtocolData<ChassisDetail> *pd =
manager.GetMutableProtocolDataById(Aebdiagresp718::ID);
EXPECT_NE(pd, nullptr);
EXPECT_EQ(static_cast<Aebdiagresp718 *>(pd)->ID, Aebdiagresp718::ID);
}
TEST_F(Neolix_eduMessageManagerTest, Aebfrontwheelspeed353) {
Neolix_eduMessageManager manager;
ProtocolData<ChassisDetail> *pd =
manager.GetMutableProtocolDataById(Aebfrontwheelspeed353::ID);
EXPECT_NE(pd, nullptr);
EXPECT_EQ(static_cast<Aebfrontwheelspeed353 *>(pd)->ID,
Aebfrontwheelspeed353::ID);
}
TEST_F(Neolix_eduMessageManagerTest, Aebrearwheelspeed354) {
Neolix_eduMessageManager manager;
ProtocolData<ChassisDetail> *pd =
manager.GetMutableProtocolDataById(Aebrearwheelspeed354::ID);
EXPECT_NE(pd, nullptr);
EXPECT_EQ(static_cast<Aebrearwheelspeed354 *>(pd)->ID,
Aebrearwheelspeed354::ID);
}
TEST_F(Neolix_eduMessageManagerTest, Aebwheelimpulse355) {
Neolix_eduMessageManager manager;
ProtocolData<ChassisDetail> *pd =
manager.GetMutableProtocolDataById(Aebwheelimpulse355::ID);
EXPECT_NE(pd, nullptr);
EXPECT_EQ(static_cast<Aebwheelimpulse355 *>(pd)->ID, Aebwheelimpulse355::ID);
}
TEST_F(Neolix_eduMessageManagerTest, Pas1stdata311) {
Neolix_eduMessageManager manager;
ProtocolData<ChassisDetail> *pd =
manager.GetMutableProtocolDataById(Pas1stdata311::ID);
EXPECT_NE(pd, nullptr);
EXPECT_EQ(static_cast<Pas1stdata311 *>(pd)->ID, Pas1stdata311::ID);
}
TEST_F(Neolix_eduMessageManagerTest, Pas2nddata312) {
Neolix_eduMessageManager manager;
ProtocolData<ChassisDetail> *pd =
manager.GetMutableProtocolDataById(Pas2nddata312::ID);
EXPECT_NE(pd, nullptr);
EXPECT_EQ(static_cast<Pas2nddata312 *>(pd)->ID, Pas2nddata312::ID);
}
} // namespace neolix_edu
} // namespace canbus
} // namespace apollo
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include "modules/canbus/vehicle/neolix_edu/neolix_edu_vehicle_factory.h"
#include "cyber/common/log.h"
#include "modules/canbus/vehicle/neolix_edu/neolix_edu_controller.h"
#include "modules/canbus/vehicle/neolix_edu/neolix_edu_message_manager.h"
#include "modules/common/util/util.h"
namespace apollo {
namespace canbus {
std::unique_ptr<VehicleController>
Neolix_eduVehicleFactory::CreateVehicleController() {
return std::unique_ptr<VehicleController>(
new neolix_edu::Neolix_eduController());
}
std::unique_ptr<MessageManager<::apollo::canbus::ChassisDetail>>
Neolix_eduVehicleFactory::CreateMessageManager() {
return std::unique_ptr<MessageManager<::apollo::canbus::ChassisDetail>>(
new neolix_edu::Neolix_eduMessageManager());
}
} // namespace canbus
} // namespace apollo
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
/**
* @file neolix_edu_vehicle_factory.h
*/
#pragma once
#include <memory>
#include "modules/canbus/proto/vehicle_parameter.pb.h"
#include "modules/canbus/vehicle/abstract_vehicle_factory.h"
#include "modules/canbus/vehicle/vehicle_controller.h"
#include "modules/drivers/canbus/can_comm/message_manager.h"
/**
* @namespace apollo::canbus
* @brief apollo::canbus
*/
namespace apollo {
namespace canbus {
/**
* @class Neolix_eduVehicleFactory
*
* @brief this class is inherited from AbstractVehicleFactory. It can be used to
* create controller and message manager for neolix_edu vehicle.
*/
class Neolix_eduVehicleFactory : public AbstractVehicleFactory {
public:
/**
* @brief destructor
*/
virtual ~Neolix_eduVehicleFactory() = default;
/**
* @brief create neolix_edu vehicle controller
* @returns a unique_ptr that points to the created controller
*/
std::unique_ptr<VehicleController> CreateVehicleController() override;
/**
* @brief create neolix_edu message manager
* @returns a unique_ptr that points to the created message manager
*/
std::unique_ptr<MessageManager<::apollo::canbus::ChassisDetail>>
CreateMessageManager() override;
};
} // namespace canbus
} // namespace apollo
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include "modules/canbus/vehicle/neolix_edu/neolix_edu_vehicle_factory.h"
#include "gtest/gtest.h"
#include "modules/canbus/proto/vehicle_parameter.pb.h"
namespace apollo {
namespace canbus {
class Neolix_eduVehicleFactoryTest : public ::testing::Test {
public:
virtual void SetUp() {
VehicleParameter parameter;
parameter.set_brand(apollo::common::CH);
ch_factory_.SetVehicleParameter(parameter);
}
virtual void TearDown() {}
protected:
Neolix_eduVehicleFactory ch_factory_;
};
TEST_F(Neolix_eduVehicleFactoryTest, InitVehicleController) {
EXPECT_NE(ch_factory_.CreateVehicleController(), nullptr);
}
TEST_F(Neolix_eduVehicleFactoryTest, InitMessageManager) {
EXPECT_NE(ch_factory_.CreateMessageManager(), nullptr);
}
} // namespace canbus
} // namespace apollo
load("@rules_cc//cc:defs.bzl", "cc_library", "cc_test")
load("//tools:cpplint.bzl", "cpplint")
package(default_visibility = ["//visibility:public"])
cc_library(
name = "canbus_neolix_edu_protocol",
srcs = glob(
["*.cc"],
exclude = ["*_test.cc"],
),
hdrs = glob([
"*.h",
]),
deps = [
"//modules/canbus/proto:chassis_detail_cc_proto",
"//modules/drivers/canbus/can_comm:message_manager_base",
"//modules/drivers/canbus/common:canbus_common",
],
)
cc_test(
name = "canbus_neolix_edu_protocol_test",
size = "small",
srcs = glob(["*_test.cc"]),
deps = [
"//modules/canbus/vehicle/neolix_edu/protocol:canbus_neolix_edu_protocol",
"@com_google_googletest//:gtest_main",
],
)
cpplint()
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include "modules/canbus/vehicle/neolix_edu/protocol/ads_brake_command_46.h"
#include "modules/drivers/canbus/common/byte.h"
namespace apollo {
namespace canbus {
namespace neolix_edu {
using ::apollo::drivers::canbus::Byte;
const int32_t Adsbrakecommand46::ID = 0x46;
// public
Adsbrakecommand46::Adsbrakecommand46() { Reset(); }
uint32_t Adsbrakecommand46::GetPeriod() const {
// TODO(All) : modify every protocol's period manually
static const uint32_t PERIOD = 20 * 1000;
return PERIOD;
}
void Adsbrakecommand46::UpdateData(uint8_t* data) {
set_p_drive_enable(data, drive_enable_);
set_p_auto_brake_command(data, auto_brake_command_);
set_p_auto_parking_command(data, auto_parking_command_);
set_p_epb_rampauxiliarycommand(data, epb_rampauxiliarycommand_);
++auto_drivercmd_alivecounter_;
auto_drivercmd_alivecounter_ = (auto_drivercmd_alivecounter_) % 16;
set_p_auto_drivercmd_alivecounter(data, auto_drivercmd_alivecounter_);
auto_drivercmd_checksum_ =
data[0] ^ data[1] ^ data[2] ^ data[3] ^ data[4] ^ data[5] ^ data[6];
set_p_auto_drivercmd_checksum(data, auto_drivercmd_checksum_);
}
void Adsbrakecommand46::Reset() {
// TODO(All) : you should check this manually
drive_enable_ = false;
auto_brake_command_ = 0;
auto_parking_command_ = false;
epb_rampauxiliarycommand_ = false;
auto_drivercmd_alivecounter_ = 0;
auto_drivercmd_checksum_ = 0;
}
Adsbrakecommand46* Adsbrakecommand46::set_drive_enable(bool drive_enable) {
drive_enable_ = drive_enable;
return this;
}
// config detail: {'description': '0x0:disable ;0x1:enable', 'offset': 0.0,
// 'precision': 1.0, 'len': 1, 'name': 'Drive_Enable', 'is_signed_var': False,
// 'physical_range': '[0|0]', 'bit': 0, 'type': 'bool', 'order': 'motorola',
// 'physical_unit': ''}
void Adsbrakecommand46::set_p_drive_enable(uint8_t* data, bool drive_enable) {
int x = drive_enable;
Byte to_set(data + 0);
to_set.set_value(x, 0, 1);
}
Adsbrakecommand46* Adsbrakecommand46::set_auto_brake_command(
int auto_brake_command) {
auto_brake_command_ = auto_brake_command;
return this;
}
// config detail: {'name': 'AUTO_Brake_Command', 'offset': 0.0,
// 'precision': 1.0, 'len': 8, 'is_signed_var': False, 'physical_range':
// '[0|0]', 'bit': 23, 'type': 'int', 'order': 'motorola', 'physical_unit': ''}
void Adsbrakecommand46::set_p_auto_brake_command(uint8_t* data,
int auto_brake_command) {
auto_brake_command = ProtocolData::BoundedValue(0, 100, auto_brake_command);
int x = auto_brake_command;
Byte to_set(data + 2);
to_set.set_value(x, 0, 8);
}
Adsbrakecommand46* Adsbrakecommand46::set_auto_parking_command(
bool auto_parking_command) {
auto_parking_command_ = auto_parking_command;
return this;
}
// config detail: {'description': '0x0:Release ;0x1:Apply ', 'offset': 0.0,
// 'precision': 1.0, 'len': 1, 'name': 'AUTO_Parking_Command', 'is_signed_var':
// False, 'physical_range': '[0|0]', 'bit': 24, 'type': 'bool', 'order':
// 'motorola', 'physical_unit': ''}
void Adsbrakecommand46::set_p_auto_parking_command(uint8_t* data,
bool auto_parking_command) {
int x = auto_parking_command;
Byte to_set(data + 3);
to_set.set_value(x, 0, 1);
}
Adsbrakecommand46* Adsbrakecommand46::set_epb_rampauxiliarycommand(
bool epb_rampauxiliarycommand) {
epb_rampauxiliarycommand_ = epb_rampauxiliarycommand;
return this;
}
// config detail: {'description': '0x0:off;0x1:on', 'offset': 0.0,
// 'precision': 1.0, 'len': 1, 'name': 'EPB_RampAuxiliaryCommand',
// 'is_signed_var': False, 'physical_range': '[0|0]', 'bit': 25, 'type': 'bool',
// 'order': 'motorola', 'physical_unit': ''}
void Adsbrakecommand46::set_p_epb_rampauxiliarycommand(
uint8_t* data, bool epb_rampauxiliarycommand) {
int x = epb_rampauxiliarycommand;
Byte to_set(data + 3);
to_set.set_value(x, 1, 1);
}
Adsbrakecommand46* Adsbrakecommand46::set_auto_drivercmd_alivecounter(
int auto_drivercmd_alivecounter) {
auto_drivercmd_alivecounter_ = auto_drivercmd_alivecounter;
return this;
}
// config detail: {'name': 'AUTO_DriverCmd_AliveCounter', 'offset': 0.0,
// 'precision': 1.0, 'len': 4, 'is_signed_var': False, 'physical_range':
// '[0|0]', 'bit': 51, 'type': 'int', 'order': 'motorola', 'physical_unit': ''}
void Adsbrakecommand46::set_p_auto_drivercmd_alivecounter(
uint8_t* data, int auto_drivercmd_alivecounter) {
auto_drivercmd_alivecounter =
ProtocolData::BoundedValue(0, 15, auto_drivercmd_alivecounter);
int x = auto_drivercmd_alivecounter;
Byte to_set(data + 6);
to_set.set_value(x, 0, 4);
}
Adsbrakecommand46* Adsbrakecommand46::set_auto_drivercmd_checksum(
int auto_drivercmd_checksum) {
auto_drivercmd_checksum_ = auto_drivercmd_checksum;
return this;
}
// config detail: {'name': 'AUTO_DriverCmd_CheckSum', 'offset': 0.0,
// 'precision': 1.0, 'len': 8, 'is_signed_var': False, 'physical_range':
// '[0|0]', 'bit': 63, 'type': 'int', 'order': 'motorola', 'physical_unit': ''}
void Adsbrakecommand46::set_p_auto_drivercmd_checksum(
uint8_t* data, int auto_drivercmd_checksum) {
auto_drivercmd_checksum =
ProtocolData::BoundedValue(0, 255, auto_drivercmd_checksum);
int x = auto_drivercmd_checksum;
Byte to_set(data + 7);
to_set.set_value(x, 0, 8);
}
} // namespace neolix_edu
} // namespace canbus
} // namespace apollo
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#pragma once
#include "modules/canbus/proto/chassis_detail.pb.h"
#include "modules/drivers/canbus/can_comm/protocol_data.h"
namespace apollo {
namespace canbus {
namespace neolix_edu {
class Adsbrakecommand46 : public ::apollo::drivers::canbus::ProtocolData<
::apollo::canbus::ChassisDetail> {
public:
static const int32_t ID;
Adsbrakecommand46();
uint32_t GetPeriod() const override;
void UpdateData(uint8_t* data) override;
void Reset() override;
// config detail: {'description': '0x0:disable ;0x1:enable', 'offset': 0.0,
// 'precision': 1.0, 'len': 1, 'name': 'Drive_Enable', 'is_signed_var': False,
// 'physical_range': '[0|0]', 'bit': 0, 'type': 'bool', 'order': 'motorola',
// 'physical_unit': ''}
Adsbrakecommand46* set_drive_enable(bool drive_enable);
// config detail: {'name': 'AUTO_Brake_Command', 'offset': 0.0,
// 'precision': 1.0, 'len': 8, 'is_signed_var': False, 'physical_range':
// '[0|0]', 'bit': 23, 'type': 'int', 'order': 'motorola', 'physical_unit':
// ''}
Adsbrakecommand46* set_auto_brake_command(int auto_brake_command);
// config detail: {'description': '0x0:Release ;0x1:Apply ', 'offset': 0.0,
// 'precision': 1.0, 'len': 1, 'name': 'AUTO_Parking_Command',
// 'is_signed_var': False, 'physical_range': '[0|0]', 'bit': 24, 'type':
// 'bool', 'order': 'motorola', 'physical_unit': ''}
Adsbrakecommand46* set_auto_parking_command(bool auto_parking_command);
// config detail: {'description': '0x0:off;0x1:on', 'offset': 0.0,
// 'precision': 1.0, 'len': 1, 'name': 'EPB_RampAuxiliaryCommand',
// 'is_signed_var': False, 'physical_range': '[0|0]', 'bit': 25, 'type':
// 'bool', 'order': 'motorola', 'physical_unit': ''}
Adsbrakecommand46* set_epb_rampauxiliarycommand(
bool epb_rampauxiliarycommand);
// config detail: {'name': 'AUTO_DriverCmd_AliveCounter', 'offset': 0.0,
// 'precision': 1.0, 'len': 4, 'is_signed_var': False, 'physical_range':
// '[0|0]', 'bit': 51, 'type': 'int', 'order': 'motorola', 'physical_unit':
// ''}
Adsbrakecommand46* set_auto_drivercmd_alivecounter(
int auto_drivercmd_alivecounter);
// config detail: {'name': 'AUTO_DriverCmd_CheckSum', 'offset': 0.0,
// 'precision': 1.0, 'len': 8, 'is_signed_var': False, 'physical_range':
// '[0|0]', 'bit': 63, 'type': 'int', 'order': 'motorola', 'physical_unit':
// ''}
Adsbrakecommand46* set_auto_drivercmd_checksum(int auto_drivercmd_checksum);
private:
// config detail: {'description': '0x0:disable ;0x1:enable', 'offset': 0.0,
// 'precision': 1.0, 'len': 1, 'name': 'Drive_Enable', 'is_signed_var': False,
// 'physical_range': '[0|0]', 'bit': 0, 'type': 'bool', 'order': 'motorola',
// 'physical_unit': ''}
void set_p_drive_enable(uint8_t* data, bool drive_enable);
// config detail: {'name': 'AUTO_Brake_Command', 'offset': 0.0,
// 'precision': 1.0, 'len': 8, 'is_signed_var': False, 'physical_range':
// '[0|0]', 'bit': 23, 'type': 'int', 'order': 'motorola', 'physical_unit':
// ''}
void set_p_auto_brake_command(uint8_t* data, int auto_brake_command);
// config detail: {'description': '0x0:Release ;0x1:Apply ', 'offset': 0.0,
// 'precision': 1.0, 'len': 1, 'name': 'AUTO_Parking_Command',
// 'is_signed_var': False, 'physical_range': '[0|0]', 'bit': 24, 'type':
// 'bool', 'order': 'motorola', 'physical_unit': ''}
void set_p_auto_parking_command(uint8_t* data, bool auto_parking_command);
// config detail: {'description': '0x0:off;0x1:on', 'offset': 0.0,
// 'precision': 1.0, 'len': 1, 'name': 'EPB_RampAuxiliaryCommand',
// 'is_signed_var': False, 'physical_range': '[0|0]', 'bit': 25, 'type':
// 'bool', 'order': 'motorola', 'physical_unit': ''}
void set_p_epb_rampauxiliarycommand(uint8_t* data,
bool epb_rampauxiliarycommand);
// config detail: {'name': 'AUTO_DriverCmd_AliveCounter', 'offset': 0.0,
// 'precision': 1.0, 'len': 4, 'is_signed_var': False, 'physical_range':
// '[0|0]', 'bit': 51, 'type': 'int', 'order': 'motorola', 'physical_unit':
// ''}
void set_p_auto_drivercmd_alivecounter(uint8_t* data,
int auto_drivercmd_alivecounter);
// config detail: {'name': 'AUTO_DriverCmd_CheckSum', 'offset': 0.0,
// 'precision': 1.0, 'len': 8, 'is_signed_var': False, 'physical_range':
// '[0|0]', 'bit': 63, 'type': 'int', 'order': 'motorola', 'physical_unit':
// ''}
void set_p_auto_drivercmd_checksum(uint8_t* data,
int auto_drivercmd_checksum);
private:
bool drive_enable_;
int auto_brake_command_;
bool auto_parking_command_;
bool epb_rampauxiliarycommand_;
int auto_drivercmd_alivecounter_;
int auto_drivercmd_checksum_;
};
} // namespace neolix_edu
} // namespace canbus
} // namespace apollo
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include "modules/canbus/vehicle/neolix_edu/protocol/ads_brake_command_46.h"
#include "gtest/gtest.h"
namespace apollo {
namespace canbus {
namespace neolix_edu {
class Adsbrakecommand46Test : public ::testing::Test {
public:
virtual void SetUp() {}
};
TEST_F(Adsbrakecommand46Test, reset) {
uint8_t data[8] = {0x67, 0x62, 0x63, 0x64, 0x51, 0x52, 0x53, 0x54};
Adsbrakecommand46 accel_cmd;
EXPECT_EQ(accel_cmd.GetPeriod(), 20 * 1000);
accel_cmd.UpdateData(data);
EXPECT_EQ(data[0], 0b01100110);
EXPECT_EQ(data[1], 0b01100010);
EXPECT_EQ(data[2], 0b00000000);
EXPECT_EQ(data[3], 0b01100100);
EXPECT_EQ(data[4], 0b01010001);
EXPECT_EQ(data[5], 0b01010010);
EXPECT_EQ(data[6], 0b01010001);
EXPECT_EQ(data[7], 0b00110010);
}
} // namespace neolix_edu
} // namespace canbus
} // namespace apollo
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include "modules/canbus/vehicle/neolix_edu/protocol/ads_diagnosis_628.h"
#include "modules/drivers/canbus/common/byte.h"
namespace apollo {
namespace canbus {
namespace neolix_edu {
using ::apollo::drivers::canbus::Byte;
const int32_t Adsdiagnosis628::ID = 0x628;
// public
Adsdiagnosis628::Adsdiagnosis628() { Reset(); }
uint32_t Adsdiagnosis628::GetPeriod() const {
// TODO(All) : modify every protocol's period manually
static const uint32_t PERIOD = 20 * 1000;
return PERIOD;
}
void Adsdiagnosis628::UpdateData(uint8_t* data) {
set_p_faultrank(data, faultrank_);
set_p_adas_fault_code(data, adas_fault_code_);
set_p_adas_softwareversion(data, adas_softwareversion_);
set_p_adas_hardwareversion(data, adas_hardwareversion_);
}
void Adsdiagnosis628::Reset() {
// TODO(All) : you should check this manually
faultrank_ = 0;
adas_fault_code_ = 0;
adas_softwareversion_ = 0;
adas_hardwareversion_ = 0;
}
Adsdiagnosis628* Adsdiagnosis628::set_faultrank(int faultrank) {
faultrank_ = faultrank;
return this;
}
// config detail: {'description': '0x0:Nomal;0x1:Level 1;0x2:Level 2;0x3:Level
// 3;0x4:Level 4;0x5:Level 5;0x6:Reserved;0x7:Reserved', 'offset': 0.0,
// 'precision': 1.0, 'len': 4, 'name': 'FaultRank', 'is_signed_var': False,
// 'physical_range': '[0|5]', 'bit': 7, 'type': 'int', 'order': 'motorola',
// 'physical_unit': 'bit'}
void Adsdiagnosis628::set_p_faultrank(uint8_t* data, int faultrank) {
faultrank = ProtocolData::BoundedValue(0, 5, faultrank);
int x = faultrank;
Byte to_set(data + 0);
to_set.set_value(x, 4, 4);
}
Adsdiagnosis628* Adsdiagnosis628::set_adas_fault_code(int adas_fault_code) {
adas_fault_code_ = adas_fault_code;
return this;
}
// config detail: {'name': 'ADAS_Fault_Code', 'offset': 0.0, 'precision': 1.0,
// 'len': 24, 'is_signed_var': False, 'physical_range': '[0|65535]', 'bit': 3,
// 'type': 'int', 'order': 'motorola', 'physical_unit': ''}
void Adsdiagnosis628::set_p_adas_fault_code(uint8_t* data,
int adas_fault_code) {
adas_fault_code = ProtocolData::BoundedValue(0, 65535, adas_fault_code);
int x = adas_fault_code;
uint8_t t = 0;
t = x & 0xF;
Byte to_set0(data + 3);
to_set0.set_value(t, 4, 4);
x >>= 4;
t = x & 0xFF;
Byte to_set1(data + 2);
to_set1.set_value(t, 0, 8);
x >>= 8;
t = x & 0xFF;
Byte to_set2(data + 1);
to_set2.set_value(t, 0, 8);
x >>= 8;
t = x & 0xF;
Byte to_set3(data + 0);
to_set3.set_value(t, 0, 4);
}
Adsdiagnosis628* Adsdiagnosis628::set_adas_softwareversion(
int adas_softwareversion) {
adas_softwareversion_ = adas_softwareversion;
return this;
}
// config detail: {'name': 'ADAS_SoftwareVersion', 'offset': 0.0,
// 'precision': 1.0, 'len': 8, 'is_signed_var': False, 'physical_range':
// '[0|255]', 'bit': 55, 'type': 'int', 'order': 'motorola', 'physical_unit':
// 'bit'}
void Adsdiagnosis628::set_p_adas_softwareversion(uint8_t* data,
int adas_softwareversion) {
adas_softwareversion =
ProtocolData::BoundedValue(0, 255, adas_softwareversion);
int x = adas_softwareversion;
Byte to_set(data + 6);
to_set.set_value(x, 0, 8);
}
Adsdiagnosis628* Adsdiagnosis628::set_adas_hardwareversion(
int adas_hardwareversion) {
adas_hardwareversion_ = adas_hardwareversion;
return this;
}
// config detail: {'name': 'ADAS_HardwareVersion', 'offset': 0.0,
// 'precision': 1.0, 'len': 8, 'is_signed_var': False, 'physical_range':
// '[0|255]', 'bit': 63, 'type': 'int', 'order': 'motorola', 'physical_unit':
// 'bit'}
void Adsdiagnosis628::set_p_adas_hardwareversion(uint8_t* data,
int adas_hardwareversion) {
adas_hardwareversion =
ProtocolData::BoundedValue(0, 255, adas_hardwareversion);
int x = adas_hardwareversion;
Byte to_set(data + 7);
to_set.set_value(x, 0, 8);
}
} // namespace neolix_edu
} // namespace canbus
} // namespace apollo
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#pragma once
#include "modules/canbus/proto/chassis_detail.pb.h"
#include "modules/drivers/canbus/can_comm/protocol_data.h"
namespace apollo {
namespace canbus {
namespace neolix_edu {
class Adsdiagnosis628 : public ::apollo::drivers::canbus::ProtocolData<
::apollo::canbus::ChassisDetail> {
public:
static const int32_t ID;
Adsdiagnosis628();
uint32_t GetPeriod() const override;
void UpdateData(uint8_t* data) override;
void Reset() override;
// config detail: {'description': '0x0:Nomal;0x1:Level 1;0x2:Level 2;0x3:Level
// 3;0x4:Level 4;0x5:Level 5;0x6:Reserved;0x7:Reserved', 'offset': 0.0,
// 'precision': 1.0, 'len': 4, 'name': 'FaultRank', 'is_signed_var': False,
// 'physical_range': '[0|5]', 'bit': 7, 'type': 'int', 'order': 'motorola',
// 'physical_unit': 'bit'}
Adsdiagnosis628* set_faultrank(int faultrank);
// config detail: {'name': 'ADAS_Fault_Code', 'offset': 0.0, 'precision': 1.0,
// 'len': 24, 'is_signed_var': False, 'physical_range': '[0|65535]', 'bit': 3,
// 'type': 'int', 'order': 'motorola', 'physical_unit': ''}
Adsdiagnosis628* set_adas_fault_code(int adas_fault_code);
// config detail: {'name': 'ADAS_SoftwareVersion', 'offset': 0.0,
// 'precision': 1.0, 'len': 8, 'is_signed_var': False, 'physical_range':
// '[0|255]', 'bit': 55, 'type': 'int', 'order': 'motorola', 'physical_unit':
// 'bit'}
Adsdiagnosis628* set_adas_softwareversion(int adas_softwareversion);
// config detail: {'name': 'ADAS_HardwareVersion', 'offset': 0.0,
// 'precision': 1.0, 'len': 8, 'is_signed_var': False, 'physical_range':
// '[0|255]', 'bit': 63, 'type': 'int', 'order': 'motorola', 'physical_unit':
// 'bit'}
Adsdiagnosis628* set_adas_hardwareversion(int adas_hardwareversion);
private:
// config detail: {'description': '0x0:Nomal;0x1:Level 1;0x2:Level 2;0x3:Level
// 3;0x4:Level 4;0x5:Level 5;0x6:Reserved;0x7:Reserved', 'offset': 0.0,
// 'precision': 1.0, 'len': 4, 'name': 'FaultRank', 'is_signed_var': False,
// 'physical_range': '[0|5]', 'bit': 7, 'type': 'int', 'order': 'motorola',
// 'physical_unit': 'bit'}
void set_p_faultrank(uint8_t* data, int faultrank);
// config detail: {'name': 'ADAS_Fault_Code', 'offset': 0.0, 'precision': 1.0,
// 'len': 24, 'is_signed_var': False, 'physical_range': '[0|65535]', 'bit': 3,
// 'type': 'int', 'order': 'motorola', 'physical_unit': ''}
void set_p_adas_fault_code(uint8_t* data, int adas_fault_code);
// config detail: {'name': 'ADAS_SoftwareVersion', 'offset': 0.0,
// 'precision': 1.0, 'len': 8, 'is_signed_var': False, 'physical_range':
// '[0|255]', 'bit': 55, 'type': 'int', 'order': 'motorola', 'physical_unit':
// 'bit'}
void set_p_adas_softwareversion(uint8_t* data, int adas_softwareversion);
// config detail: {'name': 'ADAS_HardwareVersion', 'offset': 0.0,
// 'precision': 1.0, 'len': 8, 'is_signed_var': False, 'physical_range':
// '[0|255]', 'bit': 63, 'type': 'int', 'order': 'motorola', 'physical_unit':
// 'bit'}
void set_p_adas_hardwareversion(uint8_t* data, int adas_hardwareversion);
private:
int faultrank_;
int adas_fault_code_;
int adas_softwareversion_;
int adas_hardwareversion_;
};
} // namespace neolix_edu
} // namespace canbus
} // namespace apollo
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include "modules/canbus/vehicle/neolix_edu/protocol/ads_diagnosis_628.h"
#include "gtest/gtest.h"
namespace apollo {
namespace canbus {
namespace neolix_edu {
class Adsdiagnosis628Test : public ::testing::Test {
public:
virtual void SetUp() {}
};
TEST_F(Adsdiagnosis628Test, reset) {
uint8_t data[8] = {0x67, 0x62, 0x63, 0x64, 0x51, 0x52, 0x53, 0x54};
Adsdiagnosis628 accel_cmd;
EXPECT_EQ(accel_cmd.GetPeriod(), 20 * 1000);
accel_cmd.UpdateData(data);
EXPECT_EQ(data[0], 0b00000000);
EXPECT_EQ(data[1], 0b00000000);
EXPECT_EQ(data[2], 0b00000000);
EXPECT_EQ(data[3], 0b00000100);
EXPECT_EQ(data[4], 0b01010001);
EXPECT_EQ(data[5], 0b01010010);
EXPECT_EQ(data[6], 0b00000000);
EXPECT_EQ(data[7], 0b00000000);
}
} // namespace neolix_edu
} // namespace canbus
} // namespace apollo
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include "modules/canbus/vehicle/neolix_edu/protocol/ads_drive_command_50.h"
#include "modules/drivers/canbus/common/byte.h"
namespace apollo {
namespace canbus {
namespace neolix_edu {
using ::apollo::drivers::canbus::Byte;
const int32_t Adsdrivecommand50::ID = 0x50;
// public
Adsdrivecommand50::Adsdrivecommand50() { Reset(); }
uint32_t Adsdrivecommand50::GetPeriod() const {
// TODO(All) : modify every protocol's period manually
static const uint32_t PERIOD = 20 * 1000;
return PERIOD;
}
void Adsdrivecommand50::UpdateData(uint8_t* data) {
set_p_drive_enable(data, drive_enable_);
set_p_auto_shift_command(data, auto_shift_command_);
set_p_auto_drive_torque(data, auto_drive_torque_);
++auto_drivercmd_alivecounter_;
auto_drivercmd_alivecounter_ = (auto_drivercmd_alivecounter_) % 16;
set_p_auto_drivercmd_alivecounter(data, auto_drivercmd_alivecounter_);
auto_drivercmd_checksum_ =
data[0] ^ data[1] ^ data[2] ^ data[3] ^ data[4] ^ data[5] ^ data[6];
set_p_auto_drivercmd_checksum(data, auto_drivercmd_checksum_);
}
void Adsdrivecommand50::Reset() {
// TODO(All) : you should check this manually
drive_enable_ = false;
auto_shift_command_ = Ads_drive_command_50::AUTO_SHIFT_COMMAND_N;
auto_drive_torque_ = 0.0;
auto_drivercmd_alivecounter_ = 0;
auto_drivercmd_checksum_ = 0;
}
Adsdrivecommand50* Adsdrivecommand50::set_drive_enable(bool drive_enable) {
drive_enable_ = drive_enable;
return this;
}
// config detail: {'description': '0x0:disable ;0x1:enable', 'offset': 0.0,
// 'precision': 1.0, 'len': 1, 'name': 'Drive_Enable', 'is_signed_var': False,
// 'physical_range': '[0|0]', 'bit': 0, 'type': 'bool', 'order': 'motorola',
// 'physical_unit': ''}
void Adsdrivecommand50::set_p_drive_enable(uint8_t* data, bool drive_enable) {
int x = drive_enable;
Byte to_set(data + 0);
to_set.set_value(x, 0, 1);
}
Adsdrivecommand50* Adsdrivecommand50::set_auto_shift_command(
Ads_drive_command_50::Auto_shift_commandType auto_shift_command) {
auto_shift_command_ = auto_shift_command;
return this;
}
// config detail: {'description': '0x0:N ;0x1:D ;0x2:R ;0x3:Reserved ', 'enum':
// {0: 'AUTO_SHIFT_COMMAND_N', 1: 'AUTO_SHIFT_COMMAND_D', 2:
// 'AUTO_SHIFT_COMMAND_R', 3: 'AUTO_SHIFT_COMMAND_RESERVED'}, 'precision': 1.0,
// 'len': 2, 'name': 'AUTO_Shift_Command', 'is_signed_var': False, 'offset':
// 0.0, 'physical_range': '[0|3]', 'bit': 9, 'type': 'enum', 'order':
// 'motorola', 'physical_unit': ''}
void Adsdrivecommand50::set_p_auto_shift_command(
uint8_t* data,
Ads_drive_command_50::Auto_shift_commandType auto_shift_command) {
int x = auto_shift_command;
Byte to_set(data + 1);
to_set.set_value(x, 0, 2);
}
Adsdrivecommand50* Adsdrivecommand50::set_auto_drive_torque(
double auto_drive_torque) {
auto_drive_torque_ = auto_drive_torque;
return this;
}
// config detail: {'name': 'AUTO_Drive_Torque', 'offset': -665.0, 'precision':
// 0.02, 'len': 16, 'is_signed_var': False, 'physical_range': '[0|0]', 'bit':
// 23, 'type': 'double', 'order': 'motorola', 'physical_unit': ''}
void Adsdrivecommand50::set_p_auto_drive_torque(uint8_t* data,
double auto_drive_torque) {
auto_drive_torque = ProtocolData::BoundedValue(0.0, 50.0, auto_drive_torque);
int x = (auto_drive_torque - -665.000000) / 0.020000;
uint8_t t = 0;
t = x & 0xFF;
Byte to_set0(data + 3);
to_set0.set_value(t, 0, 8);
x >>= 8;
t = x & 0xFF;
Byte to_set1(data + 2);
to_set1.set_value(t, 0, 8);
}
Adsdrivecommand50* Adsdrivecommand50::set_auto_drivercmd_alivecounter(
int auto_drivercmd_alivecounter) {
auto_drivercmd_alivecounter_ = auto_drivercmd_alivecounter;
return this;
}
// config detail: {'name': 'AUTO_DriverCmd_AliveCounter', 'offset': 0.0,
// 'precision': 1.0, 'len': 4, 'is_signed_var': False, 'physical_range':
// '[0|0]', 'bit': 51, 'type': 'int', 'order': 'motorola', 'physical_unit': ''}
void Adsdrivecommand50::set_p_auto_drivercmd_alivecounter(
uint8_t* data, int auto_drivercmd_alivecounter) {
auto_drivercmd_alivecounter =
ProtocolData::BoundedValue(0, 15, auto_drivercmd_alivecounter);
int x = auto_drivercmd_alivecounter;
Byte to_set(data + 6);
to_set.set_value(x, 0, 4);
}
Adsdrivecommand50* Adsdrivecommand50::set_auto_drivercmd_checksum(
int auto_drivercmd_checksum) {
auto_drivercmd_checksum_ = auto_drivercmd_checksum;
return this;
}
// config detail: {'name': 'AUTO_DriverCmd_CheckSum', 'offset': 0.0,
// 'precision': 1.0, 'len': 8, 'is_signed_var': False, 'physical_range':
// '[0|0]', 'bit': 63, 'type': 'int', 'order': 'motorola', 'physical_unit': ''}
void Adsdrivecommand50::set_p_auto_drivercmd_checksum(
uint8_t* data, int auto_drivercmd_checksum) {
auto_drivercmd_checksum =
ProtocolData::BoundedValue(0, 255, auto_drivercmd_checksum);
int x = auto_drivercmd_checksum;
Byte to_set(data + 7);
to_set.set_value(x, 0, 8);
}
} // namespace neolix_edu
} // namespace canbus
} // namespace apollo
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#pragma once
#include "modules/canbus/proto/chassis_detail.pb.h"
#include "modules/drivers/canbus/can_comm/protocol_data.h"
namespace apollo {
namespace canbus {
namespace neolix_edu {
class Adsdrivecommand50 : public ::apollo::drivers::canbus::ProtocolData<
::apollo::canbus::ChassisDetail> {
public:
static const int32_t ID;
Adsdrivecommand50();
uint32_t GetPeriod() const override;
void UpdateData(uint8_t* data) override;
void Reset() override;
// config detail: {'description': '0x0:disable ;0x1:enable', 'offset': 0.0,
// 'precision': 1.0, 'len': 1, 'name': 'Drive_Enable', 'is_signed_var': False,
// 'physical_range': '[0|0]', 'bit': 0, 'type': 'bool', 'order': 'motorola',
// 'physical_unit': ''}
Adsdrivecommand50* set_drive_enable(bool drive_enable);
// config detail: {'description': '0x0:N ;0x1:D ;0x2:R ;0x3:Reserved ',
// 'enum': {0: 'AUTO_SHIFT_COMMAND_N', 1: 'AUTO_SHIFT_COMMAND_D', 2:
// 'AUTO_SHIFT_COMMAND_R', 3: 'AUTO_SHIFT_COMMAND_RESERVED'},
// 'precision': 1.0, 'len': 2, 'name': 'AUTO_Shift_Command', 'is_signed_var':
// False, 'offset': 0.0, 'physical_range': '[0|3]', 'bit': 9, 'type': 'enum',
// 'order': 'motorola', 'physical_unit': ''}
Adsdrivecommand50* set_auto_shift_command(
Ads_drive_command_50::Auto_shift_commandType auto_shift_command);
// config detail: {'name': 'AUTO_Drive_Torque', 'offset': -665.0, 'precision':
// 0.02, 'len': 16, 'is_signed_var': False, 'physical_range': '[0|0]', 'bit':
// 23, 'type': 'double', 'order': 'motorola', 'physical_unit': ''}
Adsdrivecommand50* set_auto_drive_torque(double auto_drive_torque);
// config detail: {'name': 'AUTO_DriverCmd_AliveCounter', 'offset': 0.0,
// 'precision': 1.0, 'len': 4, 'is_signed_var': False, 'physical_range':
// '[0|0]', 'bit': 51, 'type': 'int', 'order': 'motorola', 'physical_unit':
// ''}
Adsdrivecommand50* set_auto_drivercmd_alivecounter(
int auto_drivercmd_alivecounter);
// config detail: {'name': 'AUTO_DriverCmd_CheckSum', 'offset': 0.0,
// 'precision': 1.0, 'len': 8, 'is_signed_var': False, 'physical_range':
// '[0|0]', 'bit': 63, 'type': 'int', 'order': 'motorola', 'physical_unit':
// ''}
Adsdrivecommand50* set_auto_drivercmd_checksum(int auto_drivercmd_checksum);
private:
// config detail: {'description': '0x0:disable ;0x1:enable', 'offset': 0.0,
// 'precision': 1.0, 'len': 1, 'name': 'Drive_Enable', 'is_signed_var': False,
// 'physical_range': '[0|0]', 'bit': 0, 'type': 'bool', 'order': 'motorola',
// 'physical_unit': ''}
void set_p_drive_enable(uint8_t* data, bool drive_enable);
// config detail: {'description': '0x0:N ;0x1:D ;0x2:R ;0x3:Reserved ',
// 'enum': {0: 'AUTO_SHIFT_COMMAND_N', 1: 'AUTO_SHIFT_COMMAND_D', 2:
// 'AUTO_SHIFT_COMMAND_R', 3: 'AUTO_SHIFT_COMMAND_RESERVED'},
// 'precision': 1.0, 'len': 2, 'name': 'AUTO_Shift_Command', 'is_signed_var':
// False, 'offset': 0.0, 'physical_range': '[0|3]', 'bit': 9, 'type': 'enum',
// 'order': 'motorola', 'physical_unit': ''}
void set_p_auto_shift_command(
uint8_t* data,
Ads_drive_command_50::Auto_shift_commandType auto_shift_command);
// config detail: {'name': 'AUTO_Drive_Torque', 'offset': -665.0, 'precision':
// 0.02, 'len': 16, 'is_signed_var': False, 'physical_range': '[0|0]', 'bit':
// 23, 'type': 'double', 'order': 'motorola', 'physical_unit': ''}
void set_p_auto_drive_torque(uint8_t* data, double auto_drive_torque);
// config detail: {'name': 'AUTO_DriverCmd_AliveCounter', 'offset': 0.0,
// 'precision': 1.0, 'len': 4, 'is_signed_var': False, 'physical_range':
// '[0|0]', 'bit': 51, 'type': 'int', 'order': 'motorola', 'physical_unit':
// ''}
void set_p_auto_drivercmd_alivecounter(uint8_t* data,
int auto_drivercmd_alivecounter);
// config detail: {'name': 'AUTO_DriverCmd_CheckSum', 'offset': 0.0,
// 'precision': 1.0, 'len': 8, 'is_signed_var': False, 'physical_range':
// '[0|0]', 'bit': 63, 'type': 'int', 'order': 'motorola', 'physical_unit':
// ''}
void set_p_auto_drivercmd_checksum(uint8_t* data,
int auto_drivercmd_checksum);
private:
bool drive_enable_;
Ads_drive_command_50::Auto_shift_commandType auto_shift_command_;
double auto_drive_torque_;
int auto_drivercmd_alivecounter_;
int auto_drivercmd_checksum_;
};
} // namespace neolix_edu
} // namespace canbus
} // namespace apollo
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include "modules/canbus/vehicle/neolix_edu/protocol/ads_drive_command_50.h"
#include "gtest/gtest.h"
namespace apollo {
namespace canbus {
namespace neolix_edu {
class Adsdrivecommand50Test : public ::testing::Test {
public:
virtual void SetUp() {}
};
TEST_F(Adsdrivecommand50Test, reset) {
uint8_t data[8] = {0x67, 0x62, 0x63, 0x64, 0x51, 0x52, 0x53, 0x54};
Adsdrivecommand50 accel_cmd;
EXPECT_EQ(accel_cmd.GetPeriod(), 20 * 1000);
accel_cmd.UpdateData(data);
EXPECT_EQ(data[0], 0b01100110);
EXPECT_EQ(data[1], 0b01100000);
EXPECT_EQ(data[2], 0b10000001);
EXPECT_EQ(data[3], 0b11100010);
EXPECT_EQ(data[4], 0b01010001);
EXPECT_EQ(data[5], 0b01010010);
EXPECT_EQ(data[6], 0b01010001);
EXPECT_EQ(data[7], 0b00110111);
}
} // namespace neolix_edu
} // namespace canbus
} // namespace apollo
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include "modules/canbus/vehicle/neolix_edu/protocol/ads_eps_command_56.h"
#include "modules/drivers/canbus/common/byte.h"
namespace apollo {
namespace canbus {
namespace neolix_edu {
using ::apollo::drivers::canbus::Byte;
const int32_t Adsepscommand56::ID = 0x56;
// public
Adsepscommand56::Adsepscommand56() { Reset(); }
uint32_t Adsepscommand56::GetPeriod() const {
// TODO(All) : modify every protocol's period manually
static const uint32_t PERIOD = 20 * 1000;
return PERIOD;
}
void Adsepscommand56::UpdateData(uint8_t* data) {
set_p_drive_enable(data, drive_enable_);
set_p_auto_target_angle(data, auto_target_angle_);
++auto_drivercmd_alivecounter_;
auto_drivercmd_alivecounter_ = (auto_drivercmd_alivecounter_) % 16;
set_p_auto_drivercmd_alivecounter(data, auto_drivercmd_alivecounter_);
auto_drivercmd_checksum_ =
data[0] ^ data[1] ^ data[2] ^ data[3] ^ data[4] ^ data[5] ^ data[6];
set_p_auto_drivercmd_checksum(data, auto_drivercmd_checksum_);
}
void Adsepscommand56::Reset() {
// TODO(All) : you should check this manually
drive_enable_ = false;
auto_target_angle_ = 0.0;
auto_drivercmd_alivecounter_ = 0;
auto_drivercmd_checksum_ = 0;
}
Adsepscommand56* Adsepscommand56::set_drive_enable(bool drive_enable) {
drive_enable_ = drive_enable;
return this;
}
// config detail: {'description': '0x0:disable ;0x1:enable', 'offset': 0.0,
// 'precision': 1.0, 'len': 1, 'name': 'Drive_Enable', 'is_signed_var': False,
// 'physical_range': '[0|0]', 'bit': 0, 'type': 'bool', 'order': 'motorola',
// 'physical_unit': ''}
void Adsepscommand56::set_p_drive_enable(uint8_t* data, bool drive_enable) {
int x = drive_enable;
Byte to_set(data + 0);
to_set.set_value(x, 0, 1);
}
Adsepscommand56* Adsepscommand56::set_auto_target_angle(
double auto_target_angle) {
auto_target_angle_ = -auto_target_angle;
return this;
}
// config detail: {'name': 'AUTO_Target_Angle', 'offset': -2048.0, 'precision':
// 0.0625, 'len': 16, 'is_signed_var': False, 'physical_range': '[0|0]', 'bit':
// 23, 'type': 'double', 'order': 'motorola', 'physical_unit': ''}
void Adsepscommand56::set_p_auto_target_angle(uint8_t* data,
double auto_target_angle) {
auto_target_angle =
ProtocolData::BoundedValue(-380.0, 380.0, auto_target_angle);
int x = (auto_target_angle - -2048.000000) / 0.062500;
uint8_t t = 0;
t = x & 0xFF;
Byte to_set0(data + 3);
to_set0.set_value(t, 0, 8);
x >>= 8;
t = x & 0xFF;
Byte to_set1(data + 2);
to_set1.set_value(t, 0, 8);
}
Adsepscommand56* Adsepscommand56::set_auto_drivercmd_alivecounter(
int auto_drivercmd_alivecounter) {
auto_drivercmd_alivecounter_ = auto_drivercmd_alivecounter;
return this;
}
// config detail: {'name': 'AUTO_DriverCmd_AliveCounter', 'offset': 0.0,
// 'precision': 1.0, 'len': 4, 'is_signed_var': False, 'physical_range':
// '[0|0]', 'bit': 51, 'type': 'int', 'order': 'motorola', 'physical_unit': ''}
void Adsepscommand56::set_p_auto_drivercmd_alivecounter(
uint8_t* data, int auto_drivercmd_alivecounter) {
auto_drivercmd_alivecounter =
ProtocolData::BoundedValue(0, 15, auto_drivercmd_alivecounter);
int x = auto_drivercmd_alivecounter;
Byte to_set(data + 6);
to_set.set_value(x, 0, 4);
}
Adsepscommand56* Adsepscommand56::set_auto_drivercmd_checksum(
int auto_drivercmd_checksum) {
auto_drivercmd_checksum_ = auto_drivercmd_checksum;
return this;
}
// config detail: {'name': 'AUTO_DriverCmd_CheckSum', 'offset': 0.0,
// 'precision': 1.0, 'len': 8, 'is_signed_var': False, 'physical_range':
// '[0|0]', 'bit': 63, 'type': 'int', 'order': 'motorola', 'physical_unit': ''}
void Adsepscommand56::set_p_auto_drivercmd_checksum(
uint8_t* data, int auto_drivercmd_checksum) {
auto_drivercmd_checksum =
ProtocolData::BoundedValue(0, 255, auto_drivercmd_checksum);
int x = auto_drivercmd_checksum;
Byte to_set(data + 7);
to_set.set_value(x, 0, 8);
}
} // namespace neolix_edu
} // namespace canbus
} // namespace apollo
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#pragma once
#include "modules/canbus/proto/chassis_detail.pb.h"
#include "modules/drivers/canbus/can_comm/protocol_data.h"
namespace apollo {
namespace canbus {
namespace neolix_edu {
class Adsepscommand56 : public ::apollo::drivers::canbus::ProtocolData<
::apollo::canbus::ChassisDetail> {
public:
static const int32_t ID;
Adsepscommand56();
uint32_t GetPeriod() const override;
void UpdateData(uint8_t* data) override;
void Reset() override;
// config detail: {'description': '0x0:disable ;0x1:enable', 'offset': 0.0,
// 'precision': 1.0, 'len': 1, 'name': 'Drive_Enable', 'is_signed_var': False,
// 'physical_range': '[0|0]', 'bit': 0, 'type': 'bool', 'order': 'motorola',
// 'physical_unit': ''}
Adsepscommand56* set_drive_enable(bool drive_enable);
// config detail: {'name': 'AUTO_Target_Angle', 'offset': -2048.0,
// 'precision': 0.0625, 'len': 16, 'is_signed_var': False, 'physical_range':
// '[0|0]', 'bit': 23, 'type': 'double', 'order': 'motorola', 'physical_unit':
// ''}
Adsepscommand56* set_auto_target_angle(double auto_target_angle);
// config detail: {'name': 'AUTO_DriverCmd_AliveCounter', 'offset': 0.0,
// 'precision': 1.0, 'len': 4, 'is_signed_var': False, 'physical_range':
// '[0|0]', 'bit': 51, 'type': 'int', 'order': 'motorola', 'physical_unit':
// ''}
Adsepscommand56* set_auto_drivercmd_alivecounter(
int auto_drivercmd_alivecounter);
// config detail: {'name': 'AUTO_DriverCmd_CheckSum', 'offset': 0.0,
// 'precision': 1.0, 'len': 8, 'is_signed_var': False, 'physical_range':
// '[0|0]', 'bit': 63, 'type': 'int', 'order': 'motorola', 'physical_unit':
// ''}
Adsepscommand56* set_auto_drivercmd_checksum(int auto_drivercmd_checksum);
private:
// config detail: {'description': '0x0:disable ;0x1:enable', 'offset': 0.0,
// 'precision': 1.0, 'len': 1, 'name': 'Drive_Enable', 'is_signed_var': False,
// 'physical_range': '[0|0]', 'bit': 0, 'type': 'bool', 'order': 'motorola',
// 'physical_unit': ''}
void set_p_drive_enable(uint8_t* data, bool drive_enable);
// config detail: {'name': 'AUTO_Target_Angle', 'offset': -2048.0,
// 'precision': 0.0625, 'len': 16, 'is_signed_var': False, 'physical_range':
// '[0|0]', 'bit': 23, 'type': 'double', 'order': 'motorola', 'physical_unit':
// ''}
void set_p_auto_target_angle(uint8_t* data, double auto_target_angle);
// config detail: {'name': 'AUTO_DriverCmd_AliveCounter', 'offset': 0.0,
// 'precision': 1.0, 'len': 4, 'is_signed_var': False, 'physical_range':
// '[0|0]', 'bit': 51, 'type': 'int', 'order': 'motorola', 'physical_unit':
// ''}
void set_p_auto_drivercmd_alivecounter(uint8_t* data,
int auto_drivercmd_alivecounter);
// config detail: {'name': 'AUTO_DriverCmd_CheckSum', 'offset': 0.0,
// 'precision': 1.0, 'len': 8, 'is_signed_var': False, 'physical_range':
// '[0|0]', 'bit': 63, 'type': 'int', 'order': 'motorola', 'physical_unit':
// ''}
void set_p_auto_drivercmd_checksum(uint8_t* data,
int auto_drivercmd_checksum);
private:
bool drive_enable_;
double auto_target_angle_;
int auto_drivercmd_alivecounter_;
int auto_drivercmd_checksum_;
};
} // namespace neolix_edu
} // namespace canbus
} // namespace apollo
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include "modules/canbus/vehicle/neolix_edu/protocol/ads_eps_command_56.h"
#include "gtest/gtest.h"
namespace apollo {
namespace canbus {
namespace neolix_edu {
class Adsepscommand56Test : public ::testing::Test {
public:
virtual void SetUp() {}
};
TEST_F(Adsepscommand56Test, reset) {
uint8_t data[8] = {0x67, 0x62, 0x63, 0x64, 0x51, 0x52, 0x53, 0x54};
Adsepscommand56 accel_cmd;
EXPECT_EQ(accel_cmd.GetPeriod(), 20 * 1000);
accel_cmd.UpdateData(data);
EXPECT_EQ(data[0], 0b01100110);
EXPECT_EQ(data[1], 0b01100010);
EXPECT_EQ(data[2], 0b10000000);
EXPECT_EQ(data[3], 0b00000000);
EXPECT_EQ(data[4], 0b01010001);
EXPECT_EQ(data[5], 0b01010010);
EXPECT_EQ(data[6], 0b01010001);
EXPECT_EQ(data[7], 0b11010110);
}
} // namespace neolix_edu
} // namespace canbus
} // namespace apollo
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include "modules/canbus/vehicle/neolix_edu/protocol/ads_light_horn_command_310.h"
#include "modules/drivers/canbus/common/byte.h"
namespace apollo {
namespace canbus {
namespace neolix_edu {
using ::apollo::drivers::canbus::Byte;
const int32_t Adslighthorncommand310::ID = 0x310;
// public
Adslighthorncommand310::Adslighthorncommand310() { Reset(); }
uint32_t Adslighthorncommand310::GetPeriod() const {
// TODO(All) : modify every protocol's period manually
static const uint32_t PERIOD = 20 * 1000;
return PERIOD;
}
void Adslighthorncommand310::UpdateData(uint8_t* data) {
set_p_turn_right_light_command(data, turn_right_light_command_);
set_p_turn_left_light_command(data, turn_left_light_command_);
set_p_horn_command(data, horn_command_);
set_p_beam_command(data, beam_command_);
++auto_drivercmd_alivecounter_;
auto_drivercmd_alivecounter_ = (auto_drivercmd_alivecounter_) % 16;
set_p_auto_drivercmd_alivecounter(data, auto_drivercmd_alivecounter_);
auto_drivercmd_checksum_ =
data[0] ^ data[1] ^ data[2] ^ data[3] ^ data[4] ^ data[5] ^ data[6];
set_p_auto_drivercmd_checksum(data, auto_drivercmd_checksum_);
}
void Adslighthorncommand310::Reset() {
// TODO(All) : you should check this manually
turn_right_light_command_ = false;
turn_left_light_command_ = false;
horn_command_ = false;
beam_command_ = 0;
auto_drivercmd_alivecounter_ = 0;
auto_drivercmd_checksum_ = 0;
}
Adslighthorncommand310* Adslighthorncommand310::set_turn_right_light_command(
bool turn_right_light_command) {
turn_right_light_command_ = turn_right_light_command;
return this;
}
// config detail: {'description': '0x0:disable ;0x1:enable', 'offset': 0.0,
// 'precision': 1.0, 'len': 1, 'name': 'Turn_Right_Light_Command',
// 'is_signed_var': False, 'physical_range': '[0|1]', 'bit': 8, 'type': 'bool',
// 'order': 'motorola', 'physical_unit': 'bit'}
void Adslighthorncommand310::set_p_turn_right_light_command(
uint8_t* data, bool turn_right_light_command) {
int x = turn_right_light_command;
Byte to_set(data + 1);
to_set.set_value(x, 0, 1);
}
Adslighthorncommand310* Adslighthorncommand310::set_turn_left_light_command(
bool turn_left_light_command) {
turn_left_light_command_ = turn_left_light_command;
return this;
}
// config detail: {'description': '0x0:disable ;0x1:enable ;0x2-0x3:Reserved ',
// 'offset': 0.0, 'precision': 1.0, 'len': 1, 'name': 'Turn_Left_Light_Command',
// 'is_signed_var': False, 'physical_range': '[0|1]', 'bit': 9, 'type': 'bool',
// 'order': 'motorola', 'physical_unit': 'bit'}
void Adslighthorncommand310::set_p_turn_left_light_command(
uint8_t* data, bool turn_left_light_command) {
int x = turn_left_light_command;
Byte to_set(data + 1);
to_set.set_value(x, 1, 1);
}
Adslighthorncommand310* Adslighthorncommand310::set_horn_command(
bool horn_command) {
horn_command_ = horn_command;
return this;
}
// config detail: {'name': 'Horn_Command', 'offset': 0.0, 'precision': 1.0,
// 'len': 1, 'is_signed_var': False, 'physical_range': '[0|1]', 'bit': 10,
// 'type': 'bool', 'order': 'motorola', 'physical_unit': 'bit'}
void Adslighthorncommand310::set_p_horn_command(uint8_t* data,
bool horn_command) {
int x = horn_command;
Byte to_set(data + 1);
to_set.set_value(x, 2, 1);
}
Adslighthorncommand310* Adslighthorncommand310::set_beam_command(
int beam_command) {
beam_command_ = beam_command;
return this;
}
// config detail: {'description': '0x0:Off;0x1:LowBeam;0x2:HighBeam', 'offset':
// 0.0, 'precision': 1.0, 'len': 2, 'name': 'Beam_Command', 'is_signed_var':
// False, 'physical_range': '[0|1]', 'bit': 13, 'type': 'int', 'order':
// 'motorola', 'physical_unit': 'bit'}
void Adslighthorncommand310::set_p_beam_command(uint8_t* data,
int beam_command) {
beam_command = ProtocolData::BoundedValue(0, 1, beam_command);
int x = beam_command;
Byte to_set(data + 1);
to_set.set_value(x, 4, 2);
}
Adslighthorncommand310* Adslighthorncommand310::set_auto_drivercmd_alivecounter(
int auto_drivercmd_alivecounter) {
auto_drivercmd_alivecounter_ = auto_drivercmd_alivecounter;
return this;
}
// config detail: {'name': 'AUTO_DriverCmd_AliveCounter', 'offset': 0.0,
// 'precision': 1.0, 'len': 4, 'is_signed_var': False, 'physical_range':
// '[0|0]', 'bit': 51, 'type': 'int', 'order': 'motorola', 'physical_unit': ''}
void Adslighthorncommand310::set_p_auto_drivercmd_alivecounter(
uint8_t* data, int auto_drivercmd_alivecounter) {
auto_drivercmd_alivecounter =
ProtocolData::BoundedValue(0, 15, auto_drivercmd_alivecounter);
int x = auto_drivercmd_alivecounter;
Byte to_set(data + 6);
to_set.set_value(x, 0, 4);
}
Adslighthorncommand310* Adslighthorncommand310::set_auto_drivercmd_checksum(
int auto_drivercmd_checksum) {
auto_drivercmd_checksum_ = auto_drivercmd_checksum;
return this;
}
// config detail: {'name': 'AUTO_DriverCmd_CheckSum', 'offset': 0.0,
// 'precision': 1.0, 'len': 8, 'is_signed_var': False, 'physical_range':
// '[0|0]', 'bit': 63, 'type': 'int', 'order': 'motorola', 'physical_unit': ''}
void Adslighthorncommand310::set_p_auto_drivercmd_checksum(
uint8_t* data, int auto_drivercmd_checksum) {
auto_drivercmd_checksum =
ProtocolData::BoundedValue(0, 255, auto_drivercmd_checksum);
int x = auto_drivercmd_checksum;
Byte to_set(data + 7);
to_set.set_value(x, 0, 8);
}
} // namespace neolix_edu
} // namespace canbus
} // namespace apollo
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#pragma once
#include "modules/canbus/proto/chassis_detail.pb.h"
#include "modules/drivers/canbus/can_comm/protocol_data.h"
namespace apollo {
namespace canbus {
namespace neolix_edu {
class Adslighthorncommand310 : public ::apollo::drivers::canbus::ProtocolData<
::apollo::canbus::ChassisDetail> {
public:
static const int32_t ID;
Adslighthorncommand310();
uint32_t GetPeriod() const override;
void UpdateData(uint8_t* data) override;
void Reset() override;
// config detail: {'description': '0x0:disable ;0x1:enable', 'offset': 0.0,
// 'precision': 1.0, 'len': 1, 'name': 'Turn_Right_Light_Command',
// 'is_signed_var': False, 'physical_range': '[0|1]', 'bit': 8, 'type':
// 'bool', 'order': 'motorola', 'physical_unit': 'bit'}
Adslighthorncommand310* set_turn_right_light_command(
bool turn_right_light_command);
// config detail: {'description': '0x0:disable ;0x1:enable ;0x2-0x3:Reserved
// ', 'offset': 0.0, 'precision': 1.0, 'len': 1, 'name':
// 'Turn_Left_Light_Command', 'is_signed_var': False, 'physical_range':
// '[0|1]', 'bit': 9, 'type': 'bool', 'order': 'motorola', 'physical_unit':
// 'bit'}
Adslighthorncommand310* set_turn_left_light_command(
bool turn_left_light_command);
// config detail: {'name': 'Horn_Command', 'offset': 0.0, 'precision': 1.0,
// 'len': 1, 'is_signed_var': False, 'physical_range': '[0|1]', 'bit': 10,
// 'type': 'bool', 'order': 'motorola', 'physical_unit': 'bit'}
Adslighthorncommand310* set_horn_command(bool horn_command);
// config detail: {'description': '0x0:Off;0x1:LowBeam;0x2:HighBeam',
// 'offset': 0.0, 'precision': 1.0, 'len': 2, 'name': 'Beam_Command',
// 'is_signed_var': False, 'physical_range': '[0|1]', 'bit': 13, 'type':
// 'int', 'order': 'motorola', 'physical_unit': 'bit'}
Adslighthorncommand310* set_beam_command(int beam_command);
// config detail: {'name': 'AUTO_DriverCmd_AliveCounter', 'offset': 0.0,
// 'precision': 1.0, 'len': 4, 'is_signed_var': False, 'physical_range':
// '[0|0]', 'bit': 51, 'type': 'int', 'order': 'motorola', 'physical_unit':
// ''}
Adslighthorncommand310* set_auto_drivercmd_alivecounter(
int auto_drivercmd_alivecounter);
// config detail: {'name': 'AUTO_DriverCmd_CheckSum', 'offset': 0.0,
// 'precision': 1.0, 'len': 8, 'is_signed_var': False, 'physical_range':
// '[0|0]', 'bit': 63, 'type': 'int', 'order': 'motorola', 'physical_unit':
// ''}
Adslighthorncommand310* set_auto_drivercmd_checksum(
int auto_drivercmd_checksum);
private:
// config detail: {'description': '0x0:disable ;0x1:enable', 'offset': 0.0,
// 'precision': 1.0, 'len': 1, 'name': 'Turn_Right_Light_Command',
// 'is_signed_var': False, 'physical_range': '[0|1]', 'bit': 8, 'type':
// 'bool', 'order': 'motorola', 'physical_unit': 'bit'}
void set_p_turn_right_light_command(uint8_t* data,
bool turn_right_light_command);
// config detail: {'description': '0x0:disable ;0x1:enable ;0x2-0x3:Reserved
// ', 'offset': 0.0, 'precision': 1.0, 'len': 1, 'name':
// 'Turn_Left_Light_Command', 'is_signed_var': False, 'physical_range':
// '[0|1]', 'bit': 9, 'type': 'bool', 'order': 'motorola', 'physical_unit':
// 'bit'}
void set_p_turn_left_light_command(uint8_t* data,
bool turn_left_light_command);
// config detail: {'name': 'Horn_Command', 'offset': 0.0, 'precision': 1.0,
// 'len': 1, 'is_signed_var': False, 'physical_range': '[0|1]', 'bit': 10,
// 'type': 'bool', 'order': 'motorola', 'physical_unit': 'bit'}
void set_p_horn_command(uint8_t* data, bool horn_command);
// config detail: {'description': '0x0:Off;0x1:LowBeam;0x2:HighBeam',
// 'offset': 0.0, 'precision': 1.0, 'len': 2, 'name': 'Beam_Command',
// 'is_signed_var': False, 'physical_range': '[0|1]', 'bit': 13, 'type':
// 'int', 'order': 'motorola', 'physical_unit': 'bit'}
void set_p_beam_command(uint8_t* data, int beam_command);
// config detail: {'name': 'AUTO_DriverCmd_AliveCounter', 'offset': 0.0,
// 'precision': 1.0, 'len': 4, 'is_signed_var': False, 'physical_range':
// '[0|0]', 'bit': 51, 'type': 'int', 'order': 'motorola', 'physical_unit':
// ''}
void set_p_auto_drivercmd_alivecounter(uint8_t* data,
int auto_drivercmd_alivecounter);
// config detail: {'name': 'AUTO_DriverCmd_CheckSum', 'offset': 0.0,
// 'precision': 1.0, 'len': 8, 'is_signed_var': False, 'physical_range':
// '[0|0]', 'bit': 63, 'type': 'int', 'order': 'motorola', 'physical_unit':
// ''}
void set_p_auto_drivercmd_checksum(uint8_t* data,
int auto_drivercmd_checksum);
private:
bool turn_right_light_command_;
bool turn_left_light_command_;
bool horn_command_;
int beam_command_;
int auto_drivercmd_alivecounter_;
int auto_drivercmd_checksum_;
};
} // namespace neolix_edu
} // namespace canbus
} // namespace apollo
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include "modules/canbus/vehicle/neolix_edu/protocol/ads_light_horn_command_310.h"
#include "gtest/gtest.h"
namespace apollo {
namespace canbus {
namespace neolix_edu {
class Adslighthorncommand310Test : public ::testing::Test {
public:
virtual void SetUp() {}
};
TEST_F(Adslighthorncommand310Test, reset) {
uint8_t data[8] = {0x67, 0x62, 0x63, 0x64, 0x51, 0x52, 0x53, 0x54};
Adslighthorncommand310 accel_cmd;
EXPECT_EQ(accel_cmd.GetPeriod(), 20 * 1000);
accel_cmd.UpdateData(data);
EXPECT_EQ(data[0], 0b01100111);
EXPECT_EQ(data[1], 0b01000000);
EXPECT_EQ(data[2], 0b01100011);
EXPECT_EQ(data[3], 0b01100100);
EXPECT_EQ(data[4], 0b01010001);
EXPECT_EQ(data[5], 0b01010010);
EXPECT_EQ(data[6], 0b01010001);
EXPECT_EQ(data[7], 0b01110010);
}
} // namespace neolix_edu
} // namespace canbus
} // namespace apollo
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_diagnosis1_626.h"
#include "glog/logging.h"
#include "modules/drivers/canbus/common/byte.h"
#include "modules/drivers/canbus/common/canbus_consts.h"
namespace apollo {
namespace canbus {
namespace neolix_edu {
using ::apollo::drivers::canbus::Byte;
Aebdiagnosis1626::Aebdiagnosis1626() {}
const int32_t Aebdiagnosis1626::ID = 0x626;
void Aebdiagnosis1626::Parse(const std::uint8_t* bytes, int32_t length,
ChassisDetail* chassis) const {
chassis->mutable_neolix_edu()
->mutable_aeb_diagnosis1_626()
->set_aeb_softwareversion(aeb_softwareversion(bytes, length));
chassis->mutable_neolix_edu()
->mutable_aeb_diagnosis1_626()
->set_aeb_hardwareversion(aeb_hardwareversion(bytes, length));
}
// config detail: {'name': 'aeb_softwareversion', 'offset': 0.0,
// 'precision': 1.0, 'len': 8, 'is_signed_var': False, 'physical_range':
// '[0.0|255.0]', 'bit': 55, 'type': 'double', 'order': 'motorola',
// 'physical_unit': 'bit'}
double Aebdiagnosis1626::aeb_softwareversion(const std::uint8_t* bytes,
int32_t length) const {
Byte t0(bytes + 6);
int32_t x = t0.get_byte(0, 8);
double ret = x;
return ret;
}
// config detail: {'name': 'aeb_hardwareversion', 'offset': 0.0,
// 'precision': 1.0, 'len': 8, 'is_signed_var': False, 'physical_range':
// '[0.0|255.0]', 'bit': 63, 'type': 'double', 'order': 'motorola',
// 'physical_unit': 'bit'}
double Aebdiagnosis1626::aeb_hardwareversion(const std::uint8_t* bytes,
int32_t length) const {
Byte t0(bytes + 7);
int32_t x = t0.get_byte(0, 8);
double ret = x;
return ret;
}
} // namespace neolix_edu
} // namespace canbus
} // namespace apollo
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#pragma once
#include "modules/canbus/proto/chassis_detail.pb.h"
#include "modules/drivers/canbus/can_comm/protocol_data.h"
namespace apollo {
namespace canbus {
namespace neolix_edu {
class Aebdiagnosis1626 : public ::apollo::drivers::canbus::ProtocolData<
::apollo::canbus::ChassisDetail> {
public:
static const int32_t ID;
Aebdiagnosis1626();
void Parse(const std::uint8_t* bytes, int32_t length,
ChassisDetail* chassis) const override;
private:
// config detail: {'name': 'AEB_SoftwareVersion', 'offset': 0.0,
// 'precision': 1.0, 'len': 8, 'is_signed_var': False, 'physical_range':
// '[0.0|255.0]', 'bit': 55, 'type': 'double', 'order': 'motorola',
// 'physical_unit': 'bit'}
double aeb_softwareversion(const std::uint8_t* bytes,
const int32_t length) const;
// config detail: {'name': 'AEB_HardwareVersion', 'offset': 0.0,
// 'precision': 1.0, 'len': 8, 'is_signed_var': False, 'physical_range':
// '[0.0|255.0]', 'bit': 63, 'type': 'double', 'order': 'motorola',
// 'physical_unit': 'bit'}
double aeb_hardwareversion(const std::uint8_t* bytes,
const int32_t length) const;
};
} // namespace neolix_edu
} // namespace canbus
} // namespace apollo
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_diagnosis1_626.h"
#include "glog/logging.h"
#include "gtest/gtest.h"
#include "modules/drivers/canbus/common/canbus_consts.h"
namespace apollo {
namespace canbus {
namespace neolix_edu {
class Aebdiagnosis1626Test : public ::testing::Test {
public:
virtual void SetUp() {}
};
TEST_F(Aebdiagnosis1626Test, reset) {
uint8_t data[8] = {0x67, 0x62, 0x63, 0x64, 0x51, 0x52, 0x53, 0x54};
int32_t length = 8;
ChassisDetail cd;
Aebdiagnosis1626 accel_cmd;
accel_cmd.Parse(data, length, &cd);
EXPECT_EQ(data[0], 0b01100111);
EXPECT_EQ(data[1], 0b01100010);
EXPECT_EQ(data[2], 0b01100011);
EXPECT_EQ(data[3], 0b01100100);
EXPECT_EQ(data[4], 0b01010001);
EXPECT_EQ(data[5], 0b01010010);
EXPECT_EQ(data[6], 0b01010011);
EXPECT_EQ(data[7], 0b01010100);
EXPECT_EQ(cd.neolix_edu().aeb_diagnosis1_626().aeb_softwareversion(), 83);
EXPECT_EQ(cd.neolix_edu().aeb_diagnosis1_626().aeb_hardwareversion(), 84);
}
} // namespace neolix_edu
} // namespace canbus
} // namespace apollo
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_diagresp_718.h"
#include "glog/logging.h"
#include "modules/drivers/canbus/common/byte.h"
#include "modules/drivers/canbus/common/canbus_consts.h"
namespace apollo {
namespace canbus {
namespace neolix_edu {
using ::apollo::drivers::canbus::Byte;
Aebdiagresp718::Aebdiagresp718() {}
const int32_t Aebdiagresp718::ID = 0x718;
void Aebdiagresp718::Parse(const std::uint8_t* bytes, int32_t length,
ChassisDetail* chassis) const {
chassis->mutable_neolix_edu()->mutable_aeb_diagresp_718()->set_aeb_diagresp(
aeb_diagresp(bytes, length));
}
// config detail: {'name': 'aeb_diagresp', 'offset': 0.0, 'precision': 1.0,
// 'len': 1, 'is_signed_var': False, 'physical_range': '[0.0|1.0]', 'bit': 0,
// 'type': 'bool', 'order': 'motorola', 'physical_unit': 'bit'}
bool Aebdiagresp718::aeb_diagresp(const std::uint8_t* bytes,
int32_t length) const {
Byte t0(bytes + 0);
int32_t x = t0.get_byte(0, 1);
bool ret = x;
return ret;
}
} // namespace neolix_edu
} // namespace canbus
} // namespace apollo
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#pragma once
#include "modules/canbus/proto/chassis_detail.pb.h"
#include "modules/drivers/canbus/can_comm/protocol_data.h"
namespace apollo {
namespace canbus {
namespace neolix_edu {
class Aebdiagresp718 : public ::apollo::drivers::canbus::ProtocolData<
::apollo::canbus::ChassisDetail> {
public:
static const int32_t ID;
Aebdiagresp718();
void Parse(const std::uint8_t* bytes, int32_t length,
ChassisDetail* chassis) const override;
private:
// config detail: {'name': 'AEB_DiagResp', 'offset': 0.0, 'precision': 1.0,
// 'len': 1, 'is_signed_var': False, 'physical_range': '[0.0|1.0]', 'bit': 0,
// 'type': 'bool', 'order': 'motorola', 'physical_unit': 'bit'}
bool aeb_diagresp(const std::uint8_t* bytes, const int32_t length) const;
};
} // namespace neolix_edu
} // namespace canbus
} // namespace apollo
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_diagresp_718.h"
#include "glog/logging.h"
#include "gtest/gtest.h"
#include "modules/drivers/canbus/common/canbus_consts.h"
namespace apollo {
namespace canbus {
namespace neolix_edu {
class Aebdiagresp718Test : public ::testing::Test {
public:
virtual void SetUp() {}
};
TEST_F(Aebdiagresp718Test, reset) {
uint8_t data[8] = {0x67, 0x62, 0x63, 0x64, 0x51, 0x52, 0x53, 0x54};
int32_t length = 8;
ChassisDetail cd;
Aebdiagresp718 accel_cmd;
accel_cmd.Parse(data, length, &cd);
EXPECT_EQ(data[0], 0b01100111);
EXPECT_EQ(data[1], 0b01100010);
EXPECT_EQ(data[2], 0b01100011);
EXPECT_EQ(data[3], 0b01100100);
EXPECT_EQ(data[4], 0b01010001);
EXPECT_EQ(data[5], 0b01010010);
EXPECT_EQ(data[6], 0b01010011);
EXPECT_EQ(data[7], 0b01010100);
EXPECT_EQ(cd.neolix_edu().aeb_diagresp_718().aeb_diagresp(), true);
}
} // namespace neolix_edu
} // namespace canbus
} // namespace apollo
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_frontwheelspeed_353.h"
#include "glog/logging.h"
#include "modules/drivers/canbus/common/byte.h"
#include "modules/drivers/canbus/common/canbus_consts.h"
namespace apollo {
namespace canbus {
namespace neolix_edu {
using ::apollo::drivers::canbus::Byte;
Aebfrontwheelspeed353::Aebfrontwheelspeed353() {}
const int32_t Aebfrontwheelspeed353::ID = 0x353;
void Aebfrontwheelspeed353::Parse(const std::uint8_t* bytes, int32_t length,
ChassisDetail* chassis) const {
chassis->mutable_neolix_edu()
->mutable_aeb_frontwheelspeed_353()
->set_vehiclespeedvalid(vehiclespeedvalid(bytes, length));
chassis->mutable_neolix_edu()
->mutable_aeb_frontwheelspeed_353()
->set_vehiclespeed(vehiclespeed(bytes, length));
chassis->mutable_neolix_edu()
->mutable_aeb_frontwheelspeed_353()
->set_vehiclerealdirect(vehiclerealdirect(bytes, length));
chassis->mutable_neolix_edu()
->mutable_aeb_frontwheelspeed_353()
->set_wheelspeed_fl_valid(wheelspeed_fl_valid(bytes, length));
chassis->mutable_neolix_edu()
->mutable_aeb_frontwheelspeed_353()
->set_wheelspeed_fl(wheelspeed_fl(bytes, length));
chassis->mutable_neolix_edu()
->mutable_aeb_frontwheelspeed_353()
->set_wheelspeed_fr_valid(wheelspeed_fr_valid(bytes, length));
chassis->mutable_neolix_edu()
->mutable_aeb_frontwheelspeed_353()
->set_wheelspeed_fr(wheelspeed_fr(bytes, length));
chassis->mutable_neolix_edu()
->mutable_aeb_frontwheelspeed_353()
->set_wheelspeed_fl_direct(wheelspeed_fl_direct(bytes, length));
chassis->mutable_neolix_edu()
->mutable_aeb_frontwheelspeed_353()
->set_wheelspeed_fr_direct(wheelspeed_fr_direct(bytes, length));
chassis->mutable_neolix_edu()
->mutable_aeb_frontwheelspeed_353()
->set_alivecounter_front(alivecounter_front(bytes, length));
chassis->mutable_neolix_edu()
->mutable_aeb_frontwheelspeed_353()
->set_checksum_front(checksum_front(bytes, length));
}
// config detail: {'description': '0x0:Invalid;0x1:Valid', 'offset': 0.0,
// 'precision': 1.0, 'len': 1, 'name': 'vehiclespeedvalid', 'is_signed_var':
// False, 'physical_range': '[0.0|1.0]', 'bit': 7, 'type': 'bool', 'order':
// 'motorola', 'physical_unit': 'bit'}
bool Aebfrontwheelspeed353::vehiclespeedvalid(const std::uint8_t* bytes,
int32_t length) const {
Byte t0(bytes + 0);
int32_t x = t0.get_byte(7, 1);
bool ret = x;
return ret;
}
// config detail: {'name': 'vehiclespeed', 'offset': 0.0, 'precision': 0.05625,
// 'len': 13, 'is_signed_var': False, 'physical_range': '[0.0|460.69]', 'bit':
// 4, 'type': 'double', 'order': 'motorola', 'physical_unit': 'Km/h'}
double Aebfrontwheelspeed353::vehiclespeed(const std::uint8_t* bytes,
int32_t length) const {
Byte t0(bytes + 0);
int32_t x = t0.get_byte(0, 5);
Byte t1(bytes + 1);
int32_t t = t1.get_byte(0, 8);
x <<= 8;
x |= t;
double ret = x * 0.056250;
return ret;
}
// config detail: {'description': '0x0:Invalid;0x1:D;0x2:N;0x3:R', 'offset':
// 0.0, 'precision': 1.0, 'len': 2, 'name': 'vehiclerealdirect',
// 'is_signed_var': False, 'physical_range': '[0.0|3.0]', 'bit': 6, 'type':
// 'double', 'order': 'motorola', 'physical_unit': 'bit'}
double Aebfrontwheelspeed353::vehiclerealdirect(const std::uint8_t* bytes,
int32_t length) const {
Byte t0(bytes + 0);
int32_t x = t0.get_byte(5, 2);
double ret = x;
return ret;
}
// config detail: {'description': '0x0:Invalid;0x1:Valid', 'offset': 0.0,
// 'precision': 1.0, 'len': 1, 'name': 'wheelspeed_fl_valid', 'is_signed_var':
// False, 'physical_range': '[0.0|1.0]', 'bit': 23, 'type': 'bool', 'order':
// 'motorola', 'physical_unit': 'bit'}
bool Aebfrontwheelspeed353::wheelspeed_fl_valid(const std::uint8_t* bytes,
int32_t length) const {
Byte t0(bytes + 2);
int32_t x = t0.get_byte(7, 1);
bool ret = x;
return ret;
}
// config detail: {'name': 'wheelspeed_fl', 'offset': 0.0, 'precision': 0.01,
// 'len': 15, 'is_signed_var': False, 'physical_range': '[0.0|327.67]', 'bit':
// 22, 'type': 'double', 'order': 'motorola', 'physical_unit': 'km/h'}
double Aebfrontwheelspeed353::wheelspeed_fl(const std::uint8_t* bytes,
int32_t length) const {
Byte t0(bytes + 2);
int32_t x = t0.get_byte(0, 7);
Byte t1(bytes + 3);
int32_t t = t1.get_byte(0, 8);
x <<= 8;
x |= t;
double ret = x * 0.010000;
return ret;
}
// config detail: {'description': '0x0:Invalid;0x1:Valid', 'offset': 0.0,
// 'precision': 1.0, 'len': 1, 'name': 'wheelspeed_fr_valid', 'is_signed_var':
// False, 'physical_range': '[0.0|1.0]', 'bit': 39, 'type': 'bool', 'order':
// 'motorola', 'physical_unit': 'bit'}
bool Aebfrontwheelspeed353::wheelspeed_fr_valid(const std::uint8_t* bytes,
int32_t length) const {
Byte t0(bytes + 4);
int32_t x = t0.get_byte(7, 1);
bool ret = x;
return ret;
}
// config detail: {'name': 'wheelspeed_fr', 'offset': 0.0, 'precision': 0.01,
// 'len': 15, 'is_signed_var': False, 'physical_range': '[0.0|327.67]', 'bit':
// 38, 'type': 'double', 'order': 'motorola', 'physical_unit': 'km/h'}
double Aebfrontwheelspeed353::wheelspeed_fr(const std::uint8_t* bytes,
int32_t length) const {
Byte t0(bytes + 4);
int32_t x = t0.get_byte(0, 7);
Byte t1(bytes + 5);
int32_t t = t1.get_byte(0, 8);
x <<= 8;
x |= t;
double ret = x * 0.010000;
return ret;
}
// config detail: {'description': '0x0:Invalid;0x1:D;0x2:N;0x3:R', 'offset':
// 0.0, 'precision': 1.0, 'len': 2, 'name': 'wheelspeed_fl_direct',
// 'is_signed_var': False, 'physical_range': '[0.0|3.0]', 'bit': 53, 'type':
// 'double', 'order': 'motorola', 'physical_unit': 'bit'}
double Aebfrontwheelspeed353::wheelspeed_fl_direct(const std::uint8_t* bytes,
int32_t length) const {
Byte t0(bytes + 6);
int32_t x = t0.get_byte(4, 2);
double ret = x;
return ret;
}
// config detail: {'description': '0x0:Invalid;0x1:D;0x2:N;0x3:R', 'offset':
// 0.0, 'precision': 1.0, 'len': 2, 'name': 'wheelspeed_fr_direct',
// 'is_signed_var': False, 'physical_range': '[0.0|3.0]', 'bit': 55, 'type':
// 'double', 'order': 'motorola', 'physical_unit': 'bit'}
double Aebfrontwheelspeed353::wheelspeed_fr_direct(const std::uint8_t* bytes,
int32_t length) const {
Byte t0(bytes + 6);
int32_t x = t0.get_byte(6, 2);
double ret = x;
return ret;
}
// config detail: {'name': 'alivecounter_front', 'offset': 0.0,
// 'precision': 1.0, 'len': 4, 'is_signed_var': False, 'physical_range':
// '[0.0|15.0]', 'bit': 51, 'type': 'double', 'order': 'motorola',
// 'physical_unit': ''}
double Aebfrontwheelspeed353::alivecounter_front(const std::uint8_t* bytes,
int32_t length) const {
Byte t0(bytes + 6);
int32_t x = t0.get_byte(0, 4);
double ret = x;
return ret;
}
// config detail: {'name': 'checksum_front', 'offset': 0.0, 'precision': 1.0,
// 'len': 8, 'is_signed_var': False, 'physical_range': '[0.0|255.0]', 'bit': 63,
// 'type': 'double', 'order': 'motorola', 'physical_unit': ''}
double Aebfrontwheelspeed353::checksum_front(const std::uint8_t* bytes,
int32_t length) const {
Byte t0(bytes + 7);
int32_t x = t0.get_byte(0, 8);
double ret = x;
return ret;
}
} // namespace neolix_edu
} // namespace canbus
} // namespace apollo
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#pragma once
#include "modules/canbus/proto/chassis_detail.pb.h"
#include "modules/drivers/canbus/can_comm/protocol_data.h"
namespace apollo {
namespace canbus {
namespace neolix_edu {
class Aebfrontwheelspeed353 : public ::apollo::drivers::canbus::ProtocolData<
::apollo::canbus::ChassisDetail> {
public:
static const int32_t ID;
Aebfrontwheelspeed353();
void Parse(const std::uint8_t* bytes, int32_t length,
ChassisDetail* chassis) const override;
private:
// config detail: {'description': '0x0:Invalid;0x1:Valid', 'offset': 0.0,
// 'precision': 1.0, 'len': 1, 'name': 'VehicleSpeedValid', 'is_signed_var':
// False, 'physical_range': '[0.0|1.0]', 'bit': 7, 'type': 'bool', 'order':
// 'motorola', 'physical_unit': 'bit'}
bool vehiclespeedvalid(const std::uint8_t* bytes, const int32_t length) const;
// config detail: {'name': 'VehicleSpeed', 'offset': 0.0, 'precision':
// 0.05625, 'len': 13, 'is_signed_var': False, 'physical_range':
// '[0.0|460.69]', 'bit': 4, 'type': 'double', 'order': 'motorola',
// 'physical_unit': 'Km/h'}
double vehiclespeed(const std::uint8_t* bytes, const int32_t length) const;
// config detail: {'description': '0x0:Invalid;0x1:D;0x2:N;0x3:R', 'offset':
// 0.0, 'precision': 1.0, 'len': 2, 'name': 'VehicleRealDirect',
// 'is_signed_var': False, 'physical_range': '[0.0|3.0]', 'bit': 6, 'type':
// 'double', 'order': 'motorola', 'physical_unit': 'bit'}
double vehiclerealdirect(const std::uint8_t* bytes,
const int32_t length) const;
// config detail: {'description': '0x0:Invalid;0x1:Valid', 'offset': 0.0,
// 'precision': 1.0, 'len': 1, 'name': 'WheelSpeed_FL_Valid', 'is_signed_var':
// False, 'physical_range': '[0.0|1.0]', 'bit': 23, 'type': 'bool', 'order':
// 'motorola', 'physical_unit': 'bit'}
bool wheelspeed_fl_valid(const std::uint8_t* bytes,
const int32_t length) const;
// config detail: {'name': 'WheelSpeed_FL', 'offset': 0.0, 'precision': 0.01,
// 'len': 15, 'is_signed_var': False, 'physical_range': '[0.0|327.67]', 'bit':
// 22, 'type': 'double', 'order': 'motorola', 'physical_unit': 'km/h'}
double wheelspeed_fl(const std::uint8_t* bytes, const int32_t length) const;
// config detail: {'description': '0x0:Invalid;0x1:Valid', 'offset': 0.0,
// 'precision': 1.0, 'len': 1, 'name': 'WheelSpeed_FR_Valid', 'is_signed_var':
// False, 'physical_range': '[0.0|1.0]', 'bit': 39, 'type': 'bool', 'order':
// 'motorola', 'physical_unit': 'bit'}
bool wheelspeed_fr_valid(const std::uint8_t* bytes,
const int32_t length) const;
// config detail: {'name': 'WheelSpeed_FR', 'offset': 0.0, 'precision': 0.01,
// 'len': 15, 'is_signed_var': False, 'physical_range': '[0.0|327.67]', 'bit':
// 38, 'type': 'double', 'order': 'motorola', 'physical_unit': 'km/h'}
double wheelspeed_fr(const std::uint8_t* bytes, const int32_t length) const;
// config detail: {'description': '0x0:Invalid;0x1:D;0x2:N;0x3:R', 'offset':
// 0.0, 'precision': 1.0, 'len': 2, 'name': 'WheelSpeed_FL_Direct',
// 'is_signed_var': False, 'physical_range': '[0.0|3.0]', 'bit': 53, 'type':
// 'double', 'order': 'motorola', 'physical_unit': 'bit'}
double wheelspeed_fl_direct(const std::uint8_t* bytes,
const int32_t length) const;
// config detail: {'description': '0x0:Invalid;0x1:D;0x2:N;0x3:R', 'offset':
// 0.0, 'precision': 1.0, 'len': 2, 'name': 'WheelSpeed_FR_Direct',
// 'is_signed_var': False, 'physical_range': '[0.0|3.0]', 'bit': 55, 'type':
// 'double', 'order': 'motorola', 'physical_unit': 'bit'}
double wheelspeed_fr_direct(const std::uint8_t* bytes,
const int32_t length) const;
// config detail: {'name': 'AliveCounter_Front', 'offset': 0.0,
// 'precision': 1.0, 'len': 4, 'is_signed_var': False, 'physical_range':
// '[0.0|15.0]', 'bit': 51, 'type': 'double', 'order': 'motorola',
// 'physical_unit': ''}
double alivecounter_front(const std::uint8_t* bytes,
const int32_t length) const;
// config detail: {'name': 'Checksum_Front', 'offset': 0.0, 'precision': 1.0,
// 'len': 8, 'is_signed_var': False, 'physical_range': '[0.0|255.0]', 'bit':
// 63, 'type': 'double', 'order': 'motorola', 'physical_unit': ''}
double checksum_front(const std::uint8_t* bytes, const int32_t length) const;
};
} // namespace neolix_edu
} // namespace canbus
} // namespace apollo
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_frontwheelspeed_353.h"
#include "glog/logging.h"
#include "gtest/gtest.h"
#include "modules/drivers/canbus/common/canbus_consts.h"
namespace apollo {
namespace canbus {
namespace neolix_edu {
class Aebfrontwheelspeed353Test : public ::testing::Test {
public:
virtual void SetUp() {}
};
TEST_F(Aebfrontwheelspeed353Test, reset) {
uint8_t data[8] = {0x67, 0x62, 0x63, 0x64, 0x51, 0x52, 0x53, 0x54};
int32_t length = 8;
ChassisDetail cd;
Aebfrontwheelspeed353 accel_cmd;
accel_cmd.Parse(data, length, &cd);
EXPECT_EQ(data[0], 0b01100111);
EXPECT_EQ(data[1], 0b01100010);
EXPECT_EQ(data[2], 0b01100011);
EXPECT_EQ(data[3], 0b01100100);
EXPECT_EQ(data[4], 0b01010001);
EXPECT_EQ(data[5], 0b01010010);
EXPECT_EQ(data[6], 0b01010011);
EXPECT_EQ(data[7], 0b01010100);
EXPECT_EQ(cd.neolix_edu().aeb_frontwheelspeed_353().vehiclespeedvalid(), false);
EXPECT_DOUBLE_EQ(cd.neolix_edu().aeb_frontwheelspeed_353().vehiclespeed(), 106.3125);
EXPECT_EQ(cd.neolix_edu().aeb_frontwheelspeed_353().vehiclerealdirect(), 3);
EXPECT_EQ(cd.neolix_edu().aeb_frontwheelspeed_353().wheelspeed_fl_valid(),
false);
EXPECT_EQ(cd.neolix_edu().aeb_frontwheelspeed_353().wheelspeed_fl(), 254.44);
EXPECT_EQ(cd.neolix_edu().aeb_frontwheelspeed_353().wheelspeed_fr_valid(),
false);
EXPECT_EQ(cd.neolix_edu().aeb_frontwheelspeed_353().wheelspeed_fr(), 208.18);
EXPECT_EQ(cd.neolix_edu().aeb_frontwheelspeed_353().wheelspeed_fl_direct(),
1);
EXPECT_EQ(cd.neolix_edu().aeb_frontwheelspeed_353().wheelspeed_fr_direct(),
1);
}
} // namespace neolix_edu
} // namespace canbus
} // namespace apollo
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_rearwheelspeed_354.h"
#include "glog/logging.h"
#include "modules/drivers/canbus/common/byte.h"
#include "modules/drivers/canbus/common/canbus_consts.h"
namespace apollo {
namespace canbus {
namespace neolix_edu {
using ::apollo::drivers::canbus::Byte;
Aebrearwheelspeed354::Aebrearwheelspeed354() {}
const int32_t Aebrearwheelspeed354::ID = 0x354;
void Aebrearwheelspeed354::Parse(const std::uint8_t* bytes, int32_t length,
ChassisDetail* chassis) const {
chassis->mutable_neolix_edu()
->mutable_aeb_rearwheelspeed_354()
->set_wheelspeed_rl_valid(wheelspeed_rl_valid(bytes, length));
chassis->mutable_neolix_edu()
->mutable_aeb_rearwheelspeed_354()
->set_wheelspeed_rl(wheelspeed_rl(bytes, length));
chassis->mutable_neolix_edu()
->mutable_aeb_rearwheelspeed_354()
->set_wheelspeed_rr_valid(wheelspeed_rr_valid(bytes, length));
chassis->mutable_neolix_edu()
->mutable_aeb_rearwheelspeed_354()
->set_wheelspeed_rr(wheelspeed_rr(bytes, length));
chassis->mutable_neolix_edu()
->mutable_aeb_rearwheelspeed_354()
->set_wheelspeed_rl_direct(wheelspeed_rl_direct(bytes, length));
chassis->mutable_neolix_edu()
->mutable_aeb_rearwheelspeed_354()
->set_wheelspeed_rr_direct(wheelspeed_rr_direct(bytes, length));
chassis->mutable_neolix_edu()
->mutable_aeb_rearwheelspeed_354()
->set_alivecounter_rear(alivecounter_rear(bytes, length));
chassis->mutable_neolix_edu()
->mutable_aeb_rearwheelspeed_354()
->set_checksum_rear(checksum_rear(bytes, length));
}
// config detail: {'description': '0x0:Invalid;0x1:Valid', 'offset': 0.0,
// 'precision': 1.0, 'len': 1, 'name': 'wheelspeed_rl_valid', 'is_signed_var':
// False, 'physical_range': '[0.0|1.0]', 'bit': 23, 'type': 'bool', 'order':
// 'motorola', 'physical_unit': 'bit'}
bool Aebrearwheelspeed354::wheelspeed_rl_valid(const std::uint8_t* bytes,
int32_t length) const {
Byte t0(bytes + 2);
int32_t x = t0.get_byte(7, 1);
bool ret = x;
return ret;
}
// config detail: {'name': 'wheelspeed_rl', 'offset': 0.0, 'precision': 0.01,
// 'len': 15, 'is_signed_var': False, 'physical_range': '[0.0|327.67]', 'bit':
// 22, 'type': 'double', 'order': 'motorola', 'physical_unit': 'km/h'}
double Aebrearwheelspeed354::wheelspeed_rl(const std::uint8_t* bytes,
int32_t length) const {
Byte t0(bytes + 2);
int32_t x = t0.get_byte(0, 7);
Byte t1(bytes + 3);
int32_t t = t1.get_byte(0, 8);
x <<= 8;
x |= t;
double ret = x * 0.010000;
return ret;
}
// config detail: {'description': '0x0:Invalid;0x1:Valid', 'offset': 0.0,
// 'precision': 1.0, 'len': 1, 'name': 'wheelspeed_rr_valid', 'is_signed_var':
// False, 'physical_range': '[0.0|1.0]', 'bit': 39, 'type': 'bool', 'order':
// 'motorola', 'physical_unit': 'bit'}
bool Aebrearwheelspeed354::wheelspeed_rr_valid(const std::uint8_t* bytes,
int32_t length) const {
Byte t0(bytes + 4);
int32_t x = t0.get_byte(7, 1);
bool ret = x;
return ret;
}
// config detail: {'name': 'wheelspeed_rr', 'offset': 0.0, 'precision': 0.01,
// 'len': 15, 'is_signed_var': False, 'physical_range': '[0.0|327.67]', 'bit':
// 38, 'type': 'double', 'order': 'motorola', 'physical_unit': 'km/h'}
double Aebrearwheelspeed354::wheelspeed_rr(const std::uint8_t* bytes,
int32_t length) const {
Byte t0(bytes + 4);
int32_t x = t0.get_byte(0, 7);
Byte t1(bytes + 5);
int32_t t = t1.get_byte(0, 8);
x <<= 8;
x |= t;
double ret = x * 0.010000;
return ret;
}
// config detail: {'description': '0x0:Invalid;0x1:D;0x2:N;0x3:R', 'offset':
// 0.0, 'precision': 1.0, 'len': 2, 'name': 'wheelspeed_rl_direct',
// 'is_signed_var': False, 'physical_range': '[0.0|3.0]', 'bit': 53, 'type':
// 'double', 'order': 'motorola', 'physical_unit': 'bit'}
double Aebrearwheelspeed354::wheelspeed_rl_direct(const std::uint8_t* bytes,
int32_t length) const {
Byte t0(bytes + 6);
int32_t x = t0.get_byte(4, 2);
double ret = x;
return ret;
}
// config detail: {'description': '0x0:Invalid;0x1:D;0x2:N;0x3:R', 'offset':
// 0.0, 'precision': 1.0, 'len': 2, 'name': 'wheelspeed_rr_direct',
// 'is_signed_var': False, 'physical_range': '[0.0|3.0]', 'bit': 55, 'type':
// 'double', 'order': 'motorola', 'physical_unit': 'bit'}
double Aebrearwheelspeed354::wheelspeed_rr_direct(const std::uint8_t* bytes,
int32_t length) const {
Byte t0(bytes + 6);
int32_t x = t0.get_byte(6, 2);
double ret = x;
return ret;
}
// config detail: {'name': 'alivecounter_rear', 'offset': 0.0, 'precision': 1.0,
// 'len': 4, 'is_signed_var': False, 'physical_range': '[0.0|15.0]', 'bit': 51,
// 'type': 'double', 'order': 'motorola', 'physical_unit': ''}
double Aebrearwheelspeed354::alivecounter_rear(const std::uint8_t* bytes,
int32_t length) const {
Byte t0(bytes + 6);
int32_t x = t0.get_byte(0, 4);
double ret = x;
return ret;
}
// config detail: {'name': 'checksum_rear', 'offset': 0.0, 'precision': 1.0,
// 'len': 8, 'is_signed_var': False, 'physical_range': '[0.0|255.0]', 'bit': 63,
// 'type': 'double', 'order': 'motorola', 'physical_unit': ''}
double Aebrearwheelspeed354::checksum_rear(const std::uint8_t* bytes,
int32_t length) const {
Byte t0(bytes + 7);
int32_t x = t0.get_byte(0, 8);
double ret = x;
return ret;
}
} // namespace neolix_edu
} // namespace canbus
} // namespace apollo
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#pragma once
#include "modules/canbus/proto/chassis_detail.pb.h"
#include "modules/drivers/canbus/can_comm/protocol_data.h"
namespace apollo {
namespace canbus {
namespace neolix_edu {
class Aebrearwheelspeed354 : public ::apollo::drivers::canbus::ProtocolData<
::apollo::canbus::ChassisDetail> {
public:
static const int32_t ID;
Aebrearwheelspeed354();
void Parse(const std::uint8_t* bytes, int32_t length,
ChassisDetail* chassis) const override;
private:
// config detail: {'description': '0x0:Invalid;0x1:Valid', 'offset': 0.0,
// 'precision': 1.0, 'len': 1, 'name': 'WheelSpeed_RL_Valid', 'is_signed_var':
// False, 'physical_range': '[0.0|1.0]', 'bit': 23, 'type': 'bool', 'order':
// 'motorola', 'physical_unit': 'bit'}
bool wheelspeed_rl_valid(const std::uint8_t* bytes,
const int32_t length) const;
// config detail: {'name': 'WheelSpeed_RL', 'offset': 0.0, 'precision': 0.01,
// 'len': 15, 'is_signed_var': False, 'physical_range': '[0.0|327.67]', 'bit':
// 22, 'type': 'double', 'order': 'motorola', 'physical_unit': 'km/h'}
double wheelspeed_rl(const std::uint8_t* bytes, const int32_t length) const;
// config detail: {'description': '0x0:Invalid;0x1:Valid', 'offset': 0.0,
// 'precision': 1.0, 'len': 1, 'name': 'WheelSpeed_RR_Valid', 'is_signed_var':
// False, 'physical_range': '[0.0|1.0]', 'bit': 39, 'type': 'bool', 'order':
// 'motorola', 'physical_unit': 'bit'}
bool wheelspeed_rr_valid(const std::uint8_t* bytes,
const int32_t length) const;
// config detail: {'name': 'WheelSpeed_RR', 'offset': 0.0, 'precision': 0.01,
// 'len': 15, 'is_signed_var': False, 'physical_range': '[0.0|327.67]', 'bit':
// 38, 'type': 'double', 'order': 'motorola', 'physical_unit': 'km/h'}
double wheelspeed_rr(const std::uint8_t* bytes, const int32_t length) const;
// config detail: {'description': '0x0:Invalid;0x1:D;0x2:N;0x3:R', 'offset':
// 0.0, 'precision': 1.0, 'len': 2, 'name': 'WheelSpeed_RL_Direct',
// 'is_signed_var': False, 'physical_range': '[0.0|3.0]', 'bit': 53, 'type':
// 'double', 'order': 'motorola', 'physical_unit': 'bit'}
double wheelspeed_rl_direct(const std::uint8_t* bytes,
const int32_t length) const;
// config detail: {'description': '0x0:Invalid;0x1:D;0x2:N;0x3:R', 'offset':
// 0.0, 'precision': 1.0, 'len': 2, 'name': 'WheelSpeed_RR_Direct',
// 'is_signed_var': False, 'physical_range': '[0.0|3.0]', 'bit': 55, 'type':
// 'double', 'order': 'motorola', 'physical_unit': 'bit'}
double wheelspeed_rr_direct(const std::uint8_t* bytes,
const int32_t length) const;
// config detail: {'name': 'AliveCounter_Rear', 'offset': 0.0,
// 'precision': 1.0, 'len': 4, 'is_signed_var': False, 'physical_range':
// '[0.0|15.0]', 'bit': 51, 'type': 'double', 'order': 'motorola',
// 'physical_unit': ''}
double alivecounter_rear(const std::uint8_t* bytes,
const int32_t length) const;
// config detail: {'name': 'Checksum_Rear', 'offset': 0.0, 'precision': 1.0,
// 'len': 8, 'is_signed_var': False, 'physical_range': '[0.0|255.0]', 'bit':
// 63, 'type': 'double', 'order': 'motorola', 'physical_unit': ''}
double checksum_rear(const std::uint8_t* bytes, const int32_t length) const;
};
} // namespace neolix_edu
} // namespace canbus
} // namespace apollo
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_rearwheelspeed_354.h"
#include "glog/logging.h"
#include "gtest/gtest.h"
#include "modules/drivers/canbus/common/canbus_consts.h"
namespace apollo {
namespace canbus {
namespace neolix_edu {
class Aebrearwheelspeed354Test : public ::testing::Test {
public:
virtual void SetUp() {}
};
TEST_F(Aebrearwheelspeed354Test, reset) {
uint8_t data[8] = {0x67, 0x62, 0x63, 0x64, 0x51, 0x52, 0x53, 0x54};
int32_t length = 8;
ChassisDetail cd;
Aebrearwheelspeed354 accel_cmd;
accel_cmd.Parse(data, length, &cd);
EXPECT_EQ(data[0], 0b01100111);
EXPECT_EQ(data[1], 0b01100010);
EXPECT_EQ(data[2], 0b01100011);
EXPECT_EQ(data[3], 0b01100100);
EXPECT_EQ(data[4], 0b01010001);
EXPECT_EQ(data[5], 0b01010010);
EXPECT_EQ(data[6], 0b01010011);
EXPECT_EQ(data[7], 0b01010100);
EXPECT_EQ(cd.neolix_edu().aeb_rearwheelspeed_354().wheelspeed_rl_valid(), false);
EXPECT_EQ(cd.neolix_edu().aeb_rearwheelspeed_354().wheelspeed_rl(), 254.44);
EXPECT_EQ(cd.neolix_edu().aeb_rearwheelspeed_354().wheelspeed_rr_valid(), false);
EXPECT_EQ(cd.neolix_edu().aeb_rearwheelspeed_354().wheelspeed_rr(), 208.18);
EXPECT_EQ(cd.neolix_edu().aeb_rearwheelspeed_354().wheelspeed_rl_direct(),
1);
EXPECT_EQ(cd.neolix_edu().aeb_rearwheelspeed_354().wheelspeed_rr_direct(),
1);
}
} // namespace neolix_edu
} // namespace canbus
} // namespace apollo
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_systemstate_11.h"
#include "glog/logging.h"
#include "modules/drivers/canbus/common/byte.h"
#include "modules/drivers/canbus/common/canbus_consts.h"
namespace apollo {
namespace canbus {
namespace neolix_edu {
using ::apollo::drivers::canbus::Byte;
Aebsystemstate11::Aebsystemstate11() {}
const int32_t Aebsystemstate11::ID = 0x11;
void Aebsystemstate11::Parse(const std::uint8_t* bytes, int32_t length,
ChassisDetail* chassis) const {
chassis->mutable_neolix_edu()->mutable_aeb_systemstate_11()->set_aeb_state(
aeb_state(bytes, length));
chassis->mutable_neolix_edu()
->mutable_aeb_systemstate_11()
->set_aeb_brakestate(aeb_brakestate(bytes, length));
chassis->mutable_neolix_edu()->mutable_aeb_systemstate_11()->set_faultrank(
faultrank(bytes, length));
chassis->mutable_neolix_edu()
->mutable_aeb_systemstate_11()
->set_currenttemperature(currenttemperature(bytes, length));
chassis->mutable_neolix_edu()->mutable_aeb_systemstate_11()->set_pas_f1_stop(
pas_f1_stop(bytes, length));
chassis->mutable_neolix_edu()->mutable_aeb_systemstate_11()->set_pas_f2_stop(
pas_f2_stop(bytes, length));
chassis->mutable_neolix_edu()->mutable_aeb_systemstate_11()->set_pas_f3_stop(
pas_f3_stop(bytes, length));
chassis->mutable_neolix_edu()->mutable_aeb_systemstate_11()->set_pas_f4_stop(
pas_f4_stop(bytes, length));
chassis->mutable_neolix_edu()->mutable_aeb_systemstate_11()->set_pas_b1_stop(
pas_b1_stop(bytes, length));
chassis->mutable_neolix_edu()->mutable_aeb_systemstate_11()->set_pas_b2_stop(
pas_b2_stop(bytes, length));
chassis->mutable_neolix_edu()->mutable_aeb_systemstate_11()->set_pas_b3_stop(
pas_b3_stop(bytes, length));
chassis->mutable_neolix_edu()->mutable_aeb_systemstate_11()->set_pas_b4_stop(
pas_b4_stop(bytes, length));
chassis->mutable_neolix_edu()
->mutable_aeb_systemstate_11()
->set_aeb_livecounter_rear(aeb_livecounter_rear(bytes, length));
chassis->mutable_neolix_edu()->mutable_aeb_systemstate_11()->set_aeb_cheksum(
aeb_cheksum(bytes, length));
}
// config detail: {'description': '0x00:read only;0x01:brake enable', 'offset':
// 0.0, 'precision': 1.0, 'len': 2, 'name': 'aeb_state', 'is_signed_var': False,
// 'physical_range': '[0|1]', 'bit': 1, 'type': 'int', 'order': 'motorola',
// 'physical_unit': ''}
int Aebsystemstate11::aeb_state(const std::uint8_t* bytes,
int32_t length) const {
Byte t0(bytes + 0);
int32_t x = t0.get_byte(0, 2);
int ret = x;
return ret;
}
// config detail: {'description': '0x00:off;0x01:on', 'offset': 0.0,
// 'precision': 1.0, 'len': 1, 'name': 'aeb_brakestate', 'is_signed_var': False,
// 'physical_range': '[0|1]', 'bit': 2, 'type': 'bool', 'order': 'motorola',
// 'physical_unit': ''}
bool Aebsystemstate11::aeb_brakestate(const std::uint8_t* bytes,
int32_t length) const {
Byte t0(bytes + 0);
int32_t x = t0.get_byte(2, 1);
bool ret = x;
return ret;
}
// config detail: {'description': '0x0:Nomal;0x1:Level 1;0x2:Level 2;0x3:Level
// 3;0x4:Level 4;0x5:Level 5;0x6:Reserved;0x7:Reserved', 'offset': 0.0,
// 'precision': 1.0, 'len': 3, 'name': 'faultrank', 'is_signed_var': False,
// 'physical_range': '[0|5]', 'bit': 10, 'type': 'int', 'order': 'motorola',
// 'physical_unit': ''}
int Aebsystemstate11::faultrank(const std::uint8_t* bytes,
int32_t length) const {
Byte t0(bytes + 1);
int32_t x = t0.get_byte(0, 3);
int ret = x;
return ret;
}
// config detail: {'name': 'currenttemperature', 'offset': -40.0,
// 'precision': 1.0, 'len': 8, 'is_signed_var': False, 'physical_range':
// '[0|120]', 'bit': 23, 'type': 'int', 'order': 'motorola', 'physical_unit':
// ''}
int Aebsystemstate11::currenttemperature(const std::uint8_t* bytes,
int32_t length) const {
Byte t0(bytes + 2);
int32_t x = t0.get_byte(0, 8);
int ret = x + -40.000000;
return ret;
}
// config detail: {'description': '0x0:Normal;0x1:ActivateBrake', 'offset': 0.0,
// 'precision': 1.0, 'len': 1, 'name': 'pas_f1_stop', 'is_signed_var': False,
// 'physical_range': '[0|1]', 'bit': 24, 'type': 'bool', 'order': 'motorola',
// 'physical_unit': ''}
bool Aebsystemstate11::pas_f1_stop(const std::uint8_t* bytes,
int32_t length) const {
Byte t0(bytes + 3);
int32_t x = t0.get_byte(0, 1);
bool ret = x;
return ret;
}
// config detail: {'description': '0x0:Normal;0x1:ActivateBrake', 'offset': 0.0,
// 'precision': 1.0, 'len': 1, 'name': 'pas_f2_stop', 'is_signed_var': False,
// 'physical_range': '[0|1]', 'bit': 25, 'type': 'bool', 'order': 'motorola',
// 'physical_unit': ''}
bool Aebsystemstate11::pas_f2_stop(const std::uint8_t* bytes,
int32_t length) const {
Byte t0(bytes + 3);
int32_t x = t0.get_byte(1, 1);
bool ret = x;
return ret;
}
// config detail: {'description': '0x0:Normal;0x1:ActivateBrake', 'offset': 0.0,
// 'precision': 1.0, 'len': 1, 'name': 'pas_f3_stop', 'is_signed_var': False,
// 'physical_range': '[0|1]', 'bit': 26, 'type': 'bool', 'order': 'motorola',
// 'physical_unit': ''}
bool Aebsystemstate11::pas_f3_stop(const std::uint8_t* bytes,
int32_t length) const {
Byte t0(bytes + 3);
int32_t x = t0.get_byte(2, 1);
bool ret = x;
return ret;
}
// config detail: {'description': '0x0:Normal;0x1:ActivateBrake', 'offset': 0.0,
// 'precision': 1.0, 'len': 1, 'name': 'pas_f4_stop', 'is_signed_var': False,
// 'physical_range': '[0|1]', 'bit': 27, 'type': 'bool', 'order': 'motorola',
// 'physical_unit': ''}
bool Aebsystemstate11::pas_f4_stop(const std::uint8_t* bytes,
int32_t length) const {
Byte t0(bytes + 3);
int32_t x = t0.get_byte(3, 1);
bool ret = x;
return ret;
}
// config detail: {'description': '0x0:Normal;0x1:ActivateBrake', 'offset': 0.0,
// 'precision': 1.0, 'len': 1, 'name': 'pas_b1_stop', 'is_signed_var': False,
// 'physical_range': '[0|1]', 'bit': 28, 'type': 'bool', 'order': 'motorola',
// 'physical_unit': ''}
bool Aebsystemstate11::pas_b1_stop(const std::uint8_t* bytes,
int32_t length) const {
Byte t0(bytes + 3);
int32_t x = t0.get_byte(4, 1);
bool ret = x;
return ret;
}
// config detail: {'description': '0x0:Normal;0x1:ActivateBrake', 'offset': 0.0,
// 'precision': 1.0, 'len': 1, 'name': 'pas_b2_stop', 'is_signed_var': False,
// 'physical_range': '[0|1]', 'bit': 29, 'type': 'bool', 'order': 'motorola',
// 'physical_unit': ''}
bool Aebsystemstate11::pas_b2_stop(const std::uint8_t* bytes,
int32_t length) const {
Byte t0(bytes + 3);
int32_t x = t0.get_byte(5, 1);
bool ret = x;
return ret;
}
// config detail: {'description': '0x0:Normal;0x1:ActivateBrake', 'offset': 0.0,
// 'precision': 1.0, 'len': 1, 'name': 'pas_b3_stop', 'is_signed_var': False,
// 'physical_range': '[0|1]', 'bit': 30, 'type': 'bool', 'order': 'motorola',
// 'physical_unit': ''}
bool Aebsystemstate11::pas_b3_stop(const std::uint8_t* bytes,
int32_t length) const {
Byte t0(bytes + 3);
int32_t x = t0.get_byte(6, 1);
bool ret = x;
return ret;
}
// config detail: {'description': '0x0:Normal;0x1:ActivateBrake', 'offset': 0.0,
// 'precision': 1.0, 'len': 1, 'name': 'pas_b4_stop', 'is_signed_var': False,
// 'physical_range': '[0|1]', 'bit': 31, 'type': 'bool', 'order': 'motorola',
// 'physical_unit': ''}
bool Aebsystemstate11::pas_b4_stop(const std::uint8_t* bytes,
int32_t length) const {
Byte t0(bytes + 3);
int32_t x = t0.get_byte(7, 1);
bool ret = x;
return ret;
}
// config detail: {'name': 'aeb_livecounter_rear', 'offset': 0.0,
// 'precision': 1.0, 'len': 4, 'is_signed_var': False, 'physical_range':
// '[0|15]', 'bit': 51, 'type': 'int', 'order': 'motorola', 'physical_unit': ''}
int Aebsystemstate11::aeb_livecounter_rear(const std::uint8_t* bytes,
int32_t length) const {
Byte t0(bytes + 6);
int32_t x = t0.get_byte(0, 4);
int ret = x;
return ret;
}
// config detail: {'name': 'aeb_cheksum', 'offset': 0.0, 'precision': 1.0,
// 'len': 8, 'is_signed_var': False, 'physical_range': '[0|255]', 'bit': 63,
// 'type': 'int', 'order': 'motorola', 'physical_unit': 'bit'}
int Aebsystemstate11::aeb_cheksum(const std::uint8_t* bytes,
int32_t length) const {
Byte t0(bytes + 7);
int32_t x = t0.get_byte(0, 8);
int ret = x;
return ret;
}
} // namespace neolix_edu
} // namespace canbus
} // namespace apollo
/******************************************************************************
* Copyright 2019 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include "modules/canbus/vehicle/neolix_edu/protocol/aeb_systemstate_11.h"
#include "glog/logging.h"
#include "gtest/gtest.h"
#include "modules/drivers/canbus/common/canbus_consts.h"
namespace apollo {
namespace canbus {
namespace neolix_edu {
class Aebsystemstate11Test : public ::testing::Test {
public:
virtual void SetUp() {}
};
TEST_F(Aebsystemstate11Test, reset) {
uint8_t data[8] = {0x67, 0x62, 0x63, 0x64, 0x51, 0x52, 0x53, 0x54};
int32_t length = 8;
ChassisDetail cd;
Aebsystemstate11 accel_cmd;
accel_cmd.Parse(data, length, &cd);
EXPECT_EQ(data[0], 0b01100111);
EXPECT_EQ(data[1], 0b01100010);
EXPECT_EQ(data[2], 0b01100011);
EXPECT_EQ(data[3], 0b01100100);
EXPECT_EQ(data[4], 0b01010001);
EXPECT_EQ(data[5], 0b01010010);
EXPECT_EQ(data[6], 0b01010011);
EXPECT_EQ(data[7], 0b01010100);
EXPECT_EQ(cd.neolix_edu().aeb_systemstate_11().aeb_state(), 3);
EXPECT_EQ(cd.neolix_edu().aeb_systemstate_11().aeb_brakestate(), true);
EXPECT_EQ(cd.neolix_edu().aeb_systemstate_11().faultrank(), 2);
EXPECT_EQ(cd.neolix_edu().aeb_systemstate_11().currenttemperature(), 59);
EXPECT_EQ(cd.neolix_edu().aeb_systemstate_11().pas_f1_stop(), false);
EXPECT_EQ(cd.neolix_edu().aeb_systemstate_11().pas_f2_stop(), false);
EXPECT_EQ(cd.neolix_edu().aeb_systemstate_11().pas_f3_stop(), true);
EXPECT_EQ(cd.neolix_edu().aeb_systemstate_11().pas_f4_stop(), false);
EXPECT_EQ(cd.neolix_edu().aeb_systemstate_11().pas_b1_stop(), false);
EXPECT_EQ(cd.neolix_edu().aeb_systemstate_11().pas_b2_stop(), true);
EXPECT_EQ(cd.neolix_edu().aeb_systemstate_11().pas_b3_stop(), true);
EXPECT_EQ(cd.neolix_edu().aeb_systemstate_11().pas_b4_stop(), false);
}
} // namespace neolix_edu
} // namespace canbus
} // namespace apollo
此差异已折叠。
......@@ -2,6 +2,7 @@ load("@rules_cc//cc:defs.bzl", "cc_library", "cc_test")
load("//tools:cpplint.bzl", "cpplint")
package(default_visibility = ["//visibility:public"])
CANBUS_COPTS = ["-DMODULE_NAME=\\\"canbus\\\""]
cc_library(
......
......@@ -2,6 +2,7 @@ load("@rules_cc//cc:defs.bzl", "cc_library", "cc_test")
load("//tools:cpplint.bzl", "cpplint")
package(default_visibility = ["//visibility:public"])
CANBUS_COPTS = ["-DMODULE_NAME=\\\"canbus\\\""]
cc_library(
......
......@@ -2,6 +2,7 @@ load("@rules_cc//cc:defs.bzl", "cc_library", "cc_test")
load("//tools:cpplint.bzl", "cpplint")
package(default_visibility = ["//visibility:public"])
CANBUS_COPTS = ["-DMODULE_NAME=\\\"canbus\\\""]
cc_library(
......
......@@ -35,6 +35,7 @@ enum VehicleBrand {
ZHONGYUN = 6;
CH = 7;
DKIT = 8;
NEOLIX =9;
}
message VehicleID {
......
......@@ -12,7 +12,7 @@ cc_library(
]),
deps = [
"//modules/drivers/canbus/common:canbus_common",
"//modules/canbus/proto:canbus_proto",
"//modules/canbus/proto:chassis_detail_cc_proto",
"//modules/drivers/canbus/can_comm:message_manager_base",
],
)
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册