部分参考

Apollo Canbus模块记录(上) - 知乎 (zhihu.com)

apollo介绍之Canbus模块(八) - 知乎 (zhihu.com)

网上很多大佬都解析过canbus模块,如上面两个参考链接,讲的很清楚,但是相对比较笼统不够细节,看完后仍然对canbus模块数据流一直很模糊,在阅读大佬的帖子,Apollo canbus代码基础上,结合自己的理解写下这篇笔记做一个总结。

Canbus模块其实可以称为Chassis模块,主要的作用是反馈车当前的状态(航向,角度,速度等信息),并且发送控制命令到车线控底盘,可以说Canbus模块是车和自动驾驶软件之间的桥梁

我的理解,canbus模块起的作用就是解析车辆CAN线报文得到车辆当前状态速度、加速度等反馈给上层模块,另外接受上层模块的控制指令,将其编码为CAN线报文发到车辆CAN线上实现转向,油门,制动,换挡。

该模块结构简化图如下:

1.主程序canbus_component.cc解析

查看dag文件可知,Apollo cyber timer 以10ms的周期执行canbus_component.cc下的Proc()函数。

下面逐个介绍上述函数。

//返回canbus模块名称
std::string CanbusComponent::Name() const { return FLAGS_canbus_module_name; }
//CanbusComponent类构造函数
CanbusComponent::CanbusComponent()
//加载canbus_conf配置文件放在canbus_conf_里
bool CanbusComponent::Init() {
// 初始化can客户端...if (FLAGS_receive_guardian) {  //默认不接受guardian,因此略过guardian_cmd_reader_ = node_->CreateReader<GuardianCommand>(guardian_cmd_reader_config,[this](const std::shared_ptr<GuardianCommand> &cmd) {ADEBUG << "Received guardian data: run canbus callback.";OnGuardianCommand(*cmd);});} else {//初始化订阅控制指令话题,类似于ros订阅话题control_command_reader_ = node_->CreateReader<ControlCommand>(control_cmd_reader_config,[this](const std::shared_ptr<ControlCommand> &cmd) {ADEBUG << "Received control data: run canbus callback.";//然后只要收到消息就执行回调函数OnControlCommand(*cmd),后面介绍OnControlCommand(*cmd);   });}//创建chassis底盘反馈信息发布器chassis_writer_ = node_->CreateWriter<Chassis>(FLAGS_chassis_topic);//创建底盘详细反馈信息发布器,在模块全局设置flags文件中默认不发布chassis_detail_writer_ =node_->CreateWriter<ChassisDetail>(FLAGS_chassis_detail_topic);
//1.初始化并开启can卡硬件
//2.打开can接受器
//3.打开can发送器
//4. 开启vehicle_controller_,后续介绍
}

配置文件的路径在canbus/common/canbus_gflags.cc下被定义

// data file
DEFINE_string(canbus_conf_file,"/apollo/modules/canbus/conf/canbus_conf.pb.txt","Default canbus conf file");

canbus_conf.pb.txt

//Clear函数关闭can_sender_,can_receiver_,can_client_,vehicle_controller_
void CanbusComponent::Clear() {can_sender_.Stop();can_receiver_.Stop();can_client_->Stop();vehicle_controller_->Stop();AINFO << "Cleanup Canbus component";
}
//发布底盘信息,类似ROS发布topic,参见\apollo\modules\canbus\proto\chassis.proto
//chassis.proto中可以看到发布的chassis消息中应包含一些基本车辆状态信息
void CanbusComponent::PublishChassis() {Chassis chassis = vehicle_controller_->chassis();common::util::FillHeader(node_->Name(), &chassis);chassis_writer_->Write(chassis);ADEBUG << chassis.ShortDebugString();
}
//发布底盘的详细信息,比chassis更详细,有轮胎压力,制动压力,各部件状态故障码等
//在canbus的common\canbus_gflags.cc文件中设置是否打开发布详细底盘信息的开关
//默认关闭
void CanbusComponent::PublishChassisDetail() {ChassisDetail chassis_detail;message_manager_->GetSensorData(&chassis_detail);ADEBUG << chassis_detail.ShortDebugString();chassis_detail_writer_->Write(chassis_detail);
}
//Apollo cyber Timer定时执行该函数,定时器的周期可以在\apollo\modules\canbus\dag\canbus.dag中
//查看,默认是10ms
bool CanbusComponent::Proc() {PublishChassis();    //定期发布从车辆CAN线上读到的底盘信息,速度加速度方向盘转角制动等信息if (FLAGS_enable_chassis_detail_pub) {  //默认不发布底盘详细信息PublishChassisDetail();}return true;
}
/*前面的Init函数中,订阅了ControlCommand的消息,一收到消息就会调用该回调函数*/
void CanbusComponent::OnControlCommand(const ControlCommand &control_command) {int64_t current_timestamp = Time::Now().ToMicrosecond(); //获取当前时间,微秒级// 检查时间戳,如果控制指令的时间戳与上一次的时间戳之差小于5000微妙即5ms则说明控制指令来的太    //快,直接忽略该消息,直接返回if (current_timestamp - last_timestamp_ < FLAGS_min_cmd_interval * 1000) {ADEBUG << "Control command comes too soon. Ignore.\n Required ""FLAGS_min_cmd_interval["<< FLAGS_min_cmd_interval << "], actual time interval["<< current_timestamp - last_timestamp_ << "].";return;}last_timestamp_ = current_timestamp;ADEBUG << "Control_sequence_number:"<< control_command.header().sequence_num() << ", Time_of_delay:"<< current_timestamp -static_cast<int64_t>(control_command.header().timestamp_sec() *1e6)<< " micro seconds";if (vehicle_controller_->Update(control_command) != ErrorCode::OK) {AERROR << "Failed to process callback function OnControlCommand because ""vehicle_controller_->Update error.";return;}//无故障码的情况下,根据控制指令更新can发布器的内容,将控制指令转换成CAN报文发布到CAN线上can_sender_.Update();
}

2. 车辆CAN线收发部分代码解析

2.1 从车辆CAN线解析车辆状态信息

简单整理了下数据CAN报文接受到canbus发布chassis信息的数据流,Apollo的架构可能比较完备,反复的跳转以及各种继承指针,看起来实在是有点费劲,粗糙整理一波:

用两张图片总结一下数据流向,后面再根据具体的代码详细分析。

这部分首先从主程序canbus_component.cc入手,定时器主函数周期Proc周期性调用PublishChassis()函数,PublishChassisDetail()默认不发布不管。

bool CanbusComponent::Proc() {PublishChassis();if (FLAGS_enable_chassis_detail_pub) {PublishChassisDetail();}return true;
}

PublishChassis()函数同样在canbus_component.cc里定义:

void CanbusComponent::PublishChassis() {//通过vehcle_controller去访问底盘信息,反馈信息全部放在chassis对象里Chassis chassis = vehicle_controller_->chassis();common::util::FillHeader(node_->Name(), &chassis);//将chassis msg发布出去,类似ROSchassis_writer_->Write(chassis);ADEBUG << chassis.ShortDebugString();
}

我们看到这里vehicle_controlller_又调用成员函数chassis()去访问CAN线反馈信息。

这里有必要先了解一下vehicle_controller

参考

apollo介绍之Canbus模块(八) - 知乎 (zhihu.com)

由于不同型号的车辆的canbus命令不一样,在"modules/canbus/vehicle"中适配了不同型号车辆的canbus消息格式,所有的车都继承自Vehicle_controller基类,通过对Vehicle_controller的抽象来发送和读取canbus信息。

vehicle_controller可以视为一个模板类,只有不同车辆公共的成员函数在vehicle_controller.cc里给出了定义,有一些vehicle_controller.h里声明了但却没有在vehicle_controller.cc里定义,这些没有定义的函数是根据不同的车辆来定义的,需要看modules/canbus/vehicle里具体车辆如ch_controller.cc里的定义,具体车辆的controller继承基类vehicle_controller,实现了工厂模式。

言归正传,前面讲到vehicle_controlller_又调用成员函数chassis()去访问底盘信息,这个chassis()正是在具体车辆的controller.cc里定义的。那我们这里以modules/canbus/vehicle/ch/ch_controller.cc里的chassis()函数定义来看:

Chassis ChController::chassis() { //只解读该函数的关键代码,该函数就是用来从CAN线获取底盘信息chassis_.Clear();  //清空chassis_结构体,chassis_是proto格式生成的结构体,chassis_用来输出ChassisDetail chassis_detail;message_manager_->GetSensorData(&chassis_detail);// 21, 22, previously 1, 2if (driving_mode() == Chassis::EMERGENCY_MODE) {set_chassis_error_code(Chassis::NO_ERROR); //如果是进入紧急模式,错误码为Noerror防止误报}chassis_.set_driving_mode(driving_mode()); //填充chassis_里的驾驶模式chassis_.set_error_code(chassis_error_code()); //填充chassis_里的驾驶模式// 填充chassis_结构体引擎是否开启chassis_.set_engine_started(true);// 4 ch车无引擎转速信息(可能是没有开放此权限或者不需要相关信息)// chassis_.set_engine_rpm(0);// 5 往chassis_里填充ch车轮速信息if (chassis_detail.ch().has_ecu_status_1_515() &&chassis_detail.ch().ecu_status_1_515().has_speed()) {chassis_.set_speed_mps(static_cast<float>(chassis_detail.ch().ecu_status_1_515().speed()));} else {chassis_.set_speed_mps(0);}// 6 ch车无里程计信息// chassis_.set_odometer_m(0);// 7 ch车无油箱信息// chassis_.set_fuel_range_m(0);// 8 throttle 往chassis_结构体里填充油门开度百分比反馈信息if (chassis_detail.ch().has_throttle_status__510() &&chassis_detail.ch().throttle_status__510().has_throttle_pedal_sts()) {chassis_.set_throttle_percentage(static_cast<float>(chassis_detail.ch().throttle_status__510().throttle_pedal_sts()));} else {chassis_.set_throttle_percentage(0);}// 9 brake 往chassis_结构体里填充刹车踏板行程百分比反馈信息if (chassis_detail.ch().has_brake_status__511() &&chassis_detail.ch().brake_status__511().has_brake_pedal_sts()) {chassis_.set_brake_percentage(static_cast<float>(chassis_detail.ch().brake_status__511().brake_pedal_sts()));} else {chassis_.set_brake_percentage(0);}// 23, previously 10   gear 往chassis_结构体里填充挡位反馈信息if (chassis_detail.ch().has_gear_status_514() &&chassis_detail.ch().gear_status_514().has_gear_sts()) {Chassis::GearPosition gear_pos = Chassis::GEAR_INVALID;if (chassis_detail.ch().gear_status_514().gear_sts() ==Gear_status_514::GEAR_STS_NEUTRAL) {gear_pos = Chassis::GEAR_NEUTRAL;}if (chassis_detail.ch().gear_status_514().gear_sts() ==Gear_status_514::GEAR_STS_REVERSE) {gear_pos = Chassis::GEAR_REVERSE;}if (chassis_detail.ch().gear_status_514().gear_sts() ==Gear_status_514::GEAR_STS_DRIVE) {gear_pos = Chassis::GEAR_DRIVE;}if (chassis_detail.ch().gear_status_514().gear_sts() ==Gear_status_514::GEAR_STS_PARK) {gear_pos = Chassis::GEAR_PARKING;}chassis_.set_gear_location(gear_pos);} else {chassis_.set_gear_location(Chassis::GEAR_NONE);}// 11 steering 往chassis_结构体里填充方向盘转角百分比反馈信息if (chassis_detail.ch().has_steer_status__512() &&chassis_detail.ch().steer_status__512().has_steer_angle_sts()) {chassis_.set_steering_percentage(static_cast<float>(chassis_detail.ch().steer_status__512().steer_angle_sts() * 100.0 /vehicle_params_.max_steer_angle()));} else {chassis_.set_steering_percentage(0);}// 26...return chassis_;
}

看完ch_controller.cc里定义的chassis()函数,就是在往chassis_这个结构体里填底盘信息,信息主要来自对chassis_detail的提炼,而chassis_detai是由message_manager_>GetSensorData(&chassis_detail);调用了messanger.h里的GetSensorData()函数后将CAN报文数据解析到chassis_detail里

chassis_detail这个结构体是由proto文件定义(\apollo\modules\canbus\proto\chassis_detail.proto)

template <typename SensorType>
ErrorCode MessageManager<SensorType>::GetSensorData(SensorType *const sensor_data) {if (sensor_data == nullptr) {AERROR << "Failed to get sensor_data due to nullptr.";return ErrorCode::CANBUS_ERROR;}std::lock_guard<std::mutex> lock(sensor_data_mutex_);sensor_data->CopyFrom(sensor_data_);return ErrorCode::OK;
}

调用了messanger.h里的GetSensorData()函数 ,复制了message sensor_data_的内容到sensor_data也就是传进来的参数chassis_detail里

那么这个sensor_data_又在哪里被定义呢?那这时我们又要从canbus_component.cc看起:

CanbusComponent::Init()的146行里,CanReceiver类对象can_receiver_访问了其成员函数Start()

bool CanbusComponent::Init() { ......// 2. start receive first then sendif (can_receiver_.Start() != ErrorCode::OK) {AERROR << "Failed to start can receiver.";return false;}......return true;
}

因为是CanReceiver类对象can_receiver的成员函数,那么这个Start()自然位于can_receiver.h下,

apollo/modules/drivers/canbus/can_comm/can_receiver.h

template <typename SensorType>
::apollo::common::ErrorCode CanReceiver<SensorType>::Start() {if (is_init_ == false) {return ::apollo::common::ErrorCode::CANBUS_ERROR;}is_running_.exchange(true);async_result_ = cyber::Async(&CanReceiver<SensorType>::RecvThreadFunc, this);return ::apollo::common::ErrorCode::OK;
}

这个start函数主要又是开启了异步线程执行RecvThreadFunc这个函数,这个函数同样在can_receiver.h里被定义

template <typename SensorType>
void CanReceiver<SensorType>::RecvThreadFunc() {......while (IsRunning()) {......for (const auto &frame : buf) {uint8_t len = frame.len;uint32_t uid = frame.id;const uint8_t *data = frame.data;pt_manager_->Parse(uid, data, len); //关键死循环调用了Parse函数......}cyber::Yield();}AINFO << "Can client receiver thread stopped.";
}

我们从上面的代码可以看出,RecvThreadFunc函数里死循环调用了pt_manager_的成员函数Parse(),我们查看pt_manager_的声明发现pt_manager_是CanReceiver类的私有数据成员。

class CanReceiver {......private:MessageManager<SensorType> *pt_manager_ = nullptr;......
};

pt_manager_的类型是MessageManager类,其调用的也是MessageManager类的成员函数Parse(),MessageManager类在apollo/modules/drivers/canbus/can_comm/message_manager.h里被定义

template <typename SensorType>
void MessageManager<SensorType>::Parse(const uint32_t message_id,const uint8_t *data, int32_t length) {ProtocolData<SensorType> *protocol_data =GetMutableProtocolDataById(message_id);......{std::lock_guard<std::mutex> lock(sensor_data_mutex_);protocol_data->Parse(data, length, &sensor_data_); //关键函数}......
}

MessageManager类的成员函数Parse()中主要就是调用了protocol_data的成员函数Parse,并将解析到的报文数据存放在sensor_data_里,这样正好和前面介绍的chassis_detail串起来了,chassis_detail复制sensor_data_ message。

我们看apollo/modules/drivers/canbus/can_comm/protocol_data.h下的Parse函数定义:

template <typename SensorType>
void ProtocolData<SensorType>::Parse(const uint8_t *bytes, int32_t length,SensorType *sensor_data) const {}

可以看到这里并没有该函数详细定义,这是因为这是一个模板类,详细的Parse函数定义在其子类也就是每辆车具体的CAN报文类的成员函数里定义,我们可以看 到在apollo/modules/canbus/vehicle/ch/(这里以ch这辆车为例子),我们可以看到ch车文件夹下有很多ID, 111, 511,115等ID报文类的定义,其中command表示需要canbus发送的控制报文,status表示canbus接受的报文。

我们以brake_status__511类为例(brake_status__511.cc)

void Brakestatus511::Parse(const std::uint8_t* bytes, int32_t length,ChassisDetail* chassis) const {chassis->mutable_ch()->mutable_brake_status__511()->set_brake_pedal_en_sts(brake_pedal_en_sts(bytes, length));chassis->mutable_ch()->mutable_brake_status__511()->set_brake_pedal_sts(brake_pedal_sts(bytes, length));chassis->mutable_ch()->mutable_brake_status__511()->set_brake_err(brake_err(bytes, length));chassis->mutable_ch()->mutable_brake_status__511()->set_emergency_btn_env(emergency_btn_env(bytes, length));chassis->mutable_ch()->mutable_brake_status__511()->set_front_bump_env(front_bump_env(bytes, length));chassis->mutable_ch()->mutable_brake_status__511()->set_back_bump_env(back_bump_env(bytes, length));chassis->mutable_ch()->mutable_brake_status__511()->set_overspd_env(overspd_env(bytes, length));chassis->mutable_check_response()->set_is_esp_online(brake_pedal_en_sts(bytes, length) == 1);
}

我们可以看到这个Parse函数,将ID 511的报文解析到的各个brake相关信号存放到参数chassis里去,注意到刚刚我们通过母类传进来的第3个参数也就是指针sensor_data_,然后chassis_details复制sensor_data_,然后chassis_details中取一部分主要信息填充主程序中的chassis, 然后canbus_component.cc里的Proc()函数周期性的发布message chassis。

我们再细看看CAN报文是如何被解析的,比如看上面代码调用的brake_pedal_en_sts()就是用来从511这条报文里解析出踏板使能状态信号:

// config detail: {'description': 'brake pedal enable bit(Status)', 'enum': {0:
// 'BRAKE_PEDAL_EN_STS_DISABLE', 1: 'BRAKE_PEDAL_EN_STS_ENABLE', 2:
// 'BRAKE_PEDAL_EN_STS_TAKEOVER'}, 'precision': 1.0, 'len': 8, 'name':
// 'brake_pedal_en_sts', 'is_signed_var': False, 'offset': 0.0,
// 'physical_range': '[0|1]', 'bit': 0, 'type': 'enum', 'order': 'intel',
// 'physical_unit': ''}
Brake_status__511::Brake_pedal_en_stsType Brakestatus511::brake_pedal_en_sts(const std::uint8_t* bytes, int32_t length) const {Byte t0(bytes + 0);int32_t x = t0.get_byte(0, 8);Brake_status__511::Brake_pedal_en_stsType ret =static_cast<Brake_status__511::Brake_pedal_en_stsType>(x);return ret;
}

车辆CAN线的解析协议也就是DBC文件在每个信号解析的函数中定义。

至此,canbus接受车辆CAN报文并解析后发布给上层模块主要数据流已经分析完毕。

2.2 发送控制指令到车辆CAN线

简单整理了下controlcmd的控制命令到发到CAN线上报文的数据流:

用两张图片总结一下数据流向,后面再根据具体的代码详细分析。

从主函数canbus_component.cc开始看:

首先看Init函数

bool CanbusComponent::Init() {......cyber::ReaderConfig guardian_cmd_reader_config;guardian_cmd_reader_config.channel_name = FLAGS_guardian_topic;guardian_cmd_reader_config.pending_queue_size =FLAGS_guardian_cmd_pending_queue_size;//订阅控制命令话题,类似ROScyber::ReaderConfig control_cmd_reader_config;  control_cmd_reader_config.channel_name = FLAGS_control_command_topic;control_cmd_reader_config.pending_queue_size =FLAGS_control_cmd_pending_queue_size;......control_command_reader_ = node_->CreateReader<ControlCommand>(control_cmd_reader_config,[this](const std::shared_ptr<ControlCommand> &cmd) {ADEBUG << "Received control data: run canbus callback.";OnControlCommand(*cmd);   //每次收到控制命令就执行回调函数OnControlCommand});}......// 3. start send,can_sender_访问其成员函数Start()if (can_sender_.Start() != ErrorCode::OK) {AERROR << "Failed to start can sender.";return false;}......return true;
}

从上面代码可以看出,类似ROS subscribe 每次收到控制命令就执行回调函数OnControlCommand,另外CanSender类对象can_sender_调用其成员函数Start(),

位于apollo/modules/drivers/canbus/can_comm/can_sender.h下

template <typename SensorType>
common::ErrorCode CanSender<SensorType>::Start() {if (is_running_) {AERROR << "Cansender has already started.";return common::ErrorCode::CANBUS_ERROR;}is_running_ = true;//启动线程调用了PowerSendThreadFunc()函数thread_.reset(new std::thread([this] { PowerSendThreadFunc(); }));return common::ErrorCode::OK;
}

Start函数启动线程调用了PowerSendThreadFunc()函数,PowerSendThreadFunc也是在can_sender.h里

template <typename SensorType>
void CanSender<SensorType>::PowerSendThreadFunc() {......while (is_running_) {  //该线程在while循环执行......for (auto &message : send_messages_) {......CanFrame can_frame = message.CanFrame(); //调用can_sender.h里的CanFrame//将can_frame放进can_frames中can_frames.push_back(can_frame);//SendSingleFrame发送can_frames中的报文if (can_client_->SendSingleFrame(can_frames) != common::ErrorCode::OK) {AERROR << "Send msg failed:" << can_frame.CanFrameString();}......}......}......
}

看上述的关键代码,主要就是用一个while循环发送报文,里面调用了can_sender.h里的CanFrame()获取了更新好要发送的报文,调用can_client.h里SendSingleFrame()来实现报文的发送。

can_sender.h里的CanFrame()获取了更新好要发送的报文 can_frame_to_send_,那么谁对这个can_frame_to_send_进行了更新呢,我们后面介绍。

template <typename SensorType>
struct CanFrame SenderMessage<SensorType>::CanFrame() {std::lock_guard<std::mutex> lock(mutex_);return can_frame_to_send_;
}

can_client.h里SendSingleFrame(),调用了硬件驱动的Send()函数将报文发送了出去。

virtual apollo::common::ErrorCode SendSingleFrame(const std::vector<CanFrame> &frames) {CHECK_EQ(frames.size(), 1U)<< "frames size not equal to 1, actual frame size :" << frames.size();int32_t n = 1;return Send(frames, &n);}

现在来看看是谁更新了要发送的报文,canbus_component.cc的init函数里订阅了控制指令,然后一收到消息就会调用回调函数OnControlCommand()去更新报文,我们来看下canbus_component.cc里的回调函数OnControlCommand()

void CanbusComponent::OnControlCommand(const ControlCommand &control_command) {......//调用了vehicle_controller类的成员函数Update()if (vehicle_controller_->Update(control_command) != ErrorCode::OK) {AERROR << "Failed to process callback function OnControlCommand because ""vehicle_controller_->Update error.";return;}//调用了CanSender类的成员函数Update()can_sender_.Update();
}

我们看到这里调用了vehicle_controller的类成员函数Update(),vehicle_controller_->Update(control_command)

同时还调用了CanSender类成员函数Update,can_sender_.Update();

我们先看一下vehicle_controller类的成员函数Update

ErrorCode VehicleController::Update(const ControlCommand &control_command) {.....//全自动驾驶模式和仅纵向自动模式公共的控制指令下发if (driving_mode() == Chassis::COMPLETE_AUTO_DRIVE ||driving_mode() == Chassis::AUTO_SPEED_ONLY) {Gear(control_command.gear_location());Throttle(control_command.throttle());Acceleration(control_command.acceleration());Brake(control_command.brake());SetEpbBreak(control_command);SetLimits();}//全自动驾驶模式和仅横向自动模式公共的控制指令下发if (driving_mode() == Chassis::COMPLETE_AUTO_DRIVE ||driving_mode() == Chassis::AUTO_STEER_ONLY) {const double steering_rate_threshold = 1.0;if (control_command.steering_rate() > steering_rate_threshold) {Steer(control_command.steering_target(), control_command.steering_rate());} else {Steer(control_command.steering_target());}}//全自动驾驶模式和仅横向自动模式及仅纵向自动模式公共的控制指令下发if ((driving_mode() == Chassis::COMPLETE_AUTO_DRIVE ||driving_mode() == Chassis::AUTO_SPEED_ONLY ||driving_mode() == Chassis::AUTO_STEER_ONLY) &&control_command.has_signal()) {SetHorn(control_command);SetTurningSignal(control_command);SetBeam(control_command);}return ErrorCode::OK;
}

这里设置下发了很多控制指令,我们以Gear(control_command.gear_location())为例子,这个函数不在vehicle_controller.cc里定义,而是继承vehicle_controller类的具体车辆类的Gear()里定义,我们以ch这辆车为例,看继承vehicle_controller类的ch_controller类的成员函数(apollo/modules/canbus/vehicle/ch/ch_controller.cc)

// NEUTRAL, REVERSE, DRIVE
void ChController::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;}// 根据control_command发过来的挡位,通过实际的报文类对象gear_command_114_调用自己的成员函数 //去将挡位控制报文发下去switch (gear_position) {case Chassis::GEAR_NEUTRAL: {gear_command_114_->set_gear_cmd(Gear_command_114::GEAR_CMD_NEUTRAL);break;}case Chassis::GEAR_REVERSE: {gear_command_114_->set_gear_cmd(Gear_command_114::GEAR_CMD_REVERSE);break;}case Chassis::GEAR_DRIVE: {gear_command_114_->set_gear_cmd(Gear_command_114::GEAR_CMD_DRIVE);break;}case Chassis::GEAR_PARKING: {gear_command_114_->set_gear_cmd(Gear_command_114::GEAR_CMD_PARK);break;}case Chassis::GEAR_INVALID: {AERROR << "Gear command is invalid!";gear_command_114_->set_gear_cmd(Gear_command_114::GEAR_CMD_NEUTRAL);break;}default: {gear_command_114_->set_gear_cmd(Gear_command_114::GEAR_CMD_NEUTRAL);break;}}
}

gear_command_114_->set_gear_cmd(Gear_command_114::GEAR_CMD_DRIVE);

我们以D档为例,gear_command_114_调用了自己的成员函数set_gear_cmd()

Gear_command_114类继承ProtocolData类

Gearcommand114* Gearcommand114::set_gear_cmd(Gear_command_114::Gear_cmdType gear_cmd) {gear_cmd_ = gear_cmd;return this;
}

Gear_command_114的成员函数就是传进来的控制挡位赋值给Gear_command_114类的私有数据成员gear_cmd_。

private:Gear_command_114::Gear_cmdType gear_cmd_;

gear_cmd_属于Gear_command_114的私有数据成员,这里记住gear_cmd_,等会儿谁会将其编码发送。

我们再来看Init()函数里调用的第二个Update(),CanSender类成员函数Update,can_sender_.Update();

位于can_sender.h里定义Update函数

template <typename SensorType>
void SenderMessage<SensorType>::Update() {if (protocol_data_ == nullptr) {AERROR << "Attention: ProtocolData is nullptr!";return;}protocol_data_->UpdateData(can_frame_to_update_.data);//关键调用std::lock_guard<std::mutex> lock(mutex_);can_frame_to_send_ = can_frame_to_update_;
}

可以看到can_sender_.Update()函数里又调用了ProcotolData类对象protocol_data_的成员函数UpdateData(can_frame_to_update.data);

这个函数的作用是更新要发送的报文,同时更新完的报文赋值给can_frame_to_send_要发送的报文。

UpdateData()位于protocol_data.h里

template <typename SensorType>
void ProtocolData<SensorType>::UpdateData(uint8_t * /*data*/) {}

但当我们跳到\apollo\modules\drivers\canbus\can_comm\protocol_data.h下的UpdateData,我们可以看到这里什么都没有定义,因为这是一个母类,那些特定车辆的具体报文类继承ProtocolData类

比如说gear_command_114类里的UpdateData()函数,调用protocol_data.h里的UpdateData()函数时其实调用的是具体报文类如gear_command_114类里的UpdateData()函数。

但是具体是谁将这个protocol_data_指向具体的报文,后续再进行学习。

void Gearcommand114::UpdateData(uint8_t* data) {set_p_gear_cmd(data, gear_cmd_);
}

调用protocol_data.h里的UpdateData()函数时其实调用的是具体报文类如gear_command_114.cc类里的UpdateData()函数,这里传进来的参数data就是can_frame_to_update_.data

这里gear_command_114类里的UpdateData()函数又调用了gear_command_114类里成员函数set_p_gear_cmd()

void Gearcommand114::set_p_gear_cmd(uint8_t* data,Gear_command_114::Gear_cmdType gear_cmd) {int x = gear_cmd;Byte to_set(data + 0);to_set.set_value(static_cast<uint8_t>(x), 0, 8);
}

可以看到这里是将控制指令值编码进CAN报文can_frame_to_update_.data里。

前面介绍的Cansender类成员函数void PowerSendThreadFunc()会获取can_frame_to_send_(can_frame_to_update_赋值过来的),然后调用SendSingleFrame发送报文。

到这里报文的更新数据流介绍就结束了。

3. vehicle_controller.h

4. ch_controller.h

Apollo canbus模块学习笔记相关推荐

  1. 携程 Apollo 配置中心 | 学习笔记(七) | 如何将配置文件敏感信息加密?

    携程 Apollo 配置中心 | 学习笔记(一) Apollo配置中心简单介绍 携程 Apollo 配置中心 | 学习笔记(二) Windows 系统搭建基于携程Apollo配置中心单机模式 携程 A ...

  2. Arduino模块学习笔记(一)—GPS模块的使用

    Arduino模块学习笔记(一)--GSP模块的使用 文章目录 Arduino模块学习笔记(一)--GSP模块的使用 所需组件 一.模块使用介绍 1.GPS模块(在室内时,一般获取不到位置信息) 2. ...

  3. python模块学习笔记

    python模块学习笔记 1.Python自动发送邮件smtplib 2.制作二维码图片MyQR 3.绝对值模块math 4.CSV模块 5.openpyxl 模块,操作Excel文件 ExcelMa ...

  4. cma linux 起始地址,CMA模块学习笔记

    CMA模块学习笔记 作者:linuxer 发布于:2017-6-28 18:29 分类:内存管理 前言 本文是近期学习CMA模块的一个学习笔记,方便日后遗忘的时候,回来查询以便迅速恢复上下文. 学习的 ...

  5. 百度Apollo自动驾驶学习笔记

    Apollo学习笔记 作者:邹镇洪(清华大学车辆学院,个人主页 转到Github项目主页查看持续更新 转到Github项目主页查看持续更新 转到Github项目主页查看持续更新 本文是对百度Apoll ...

  6. Python模块之Pandas模块学习笔记

    目录 一.模块的安装 二.数据结构 1. DataFrame的创建 2. DataFrame索引的修改 3. DataFrame数据信息查看 三.文件的读取和写入 1. 读取 2. 写入 四. 数据的 ...

  7. IPy-IPv4和IPv6地址处理模块学习笔记

    在日常网络规划中,会有很多关于IP地址的分配规划问题,如果是手动分配,在量很大的情况下,容易出错.而利用IPy这个python模块,可以很容易实现对iP地址的分配等操作. 以下是对IPy模块学习的一个 ...

  8. 百度Apollo自动驾驶感知模块学习笔记、入门

    3个跟HM对象跟踪相关的对象类 Object.TrackedObject.ObjectTrack Object类:感知到的车辆信息.包含物体的点云.多边形轮廓(Polygon).类别(vehicle, ...

  9. 【Apollo 6.0学习笔记】高精地图

    文章目录 前言 什么是高精地图? 一.高精地图与各模块之间的关系 1.1 高精地图与定位模块的关系 1.2 高精地图与感知模块的关系 1.3 高精地图与规划.预测.决策模块的关系 1.4 高精地图与安 ...

  10. 《西游降魔录》模块学习笔记

    <三维游戏设计师宝典3>附带的光盘是错位的给的不是书中的例子所对应的光盘具体原因不得而知.尽管如此,该错位的光盘却有个非常好的例子<西游降魔录> 的游戏,前两天尝试着写了点自己 ...

最新文章

  1. linux系统重装后挂载数据盘,Linux重装系统后如何重新挂载数据盘?
  2. QIIME 2用户文档. 20命令行界面q2cli(2019.7)
  3. onvif规范的实现:成功实现ONVIF协议RTSP-Video-Stream与OnvifDeviceManager的视频对接
  4. python通过ip池爬_Python爬虫 | IP池的使用
  5. new关键字对类成员的阻断
  6. Python 内置模块之 random
  7. php.exe占用资源过大,记录一次php占用系统资源过高的问题
  8. 算法导论 练习14.1-7
  9. 3S基础知识:MapX应用教程—创建地图对象
  10. 想要快速扒谱?快来掌握这些小技巧吧!
  11. Smart3D三维建模操作笔记
  12. html写自动关机的代码,让电脑自动关机代码是什么
  13. 陕西2020行政区划调整_陕西行政区划调整畅想:西安咸阳合并可行,但成立直辖市不太现实...
  14. 云通信接口更新迭代——SUBMAIL API V4正式上线
  15. linux 网络速度非常慢,Linux认证:解决ubuntu8.10上网速度慢的问题
  16. 【题解】P3939数颜色
  17. 在centos上安装vmware14
  18. C 程序设计语言(第2版)
  19. 我就喜欢那种认认真真和我吵架的
  20. 保险费率软件测试题目,软件测试保险等价类法测试用例

热门文章

  1. 令牌桶 java_服务限流(自定义注解令牌桶算法)
  2. 古建筑测绘任重道远,三维实景建模是唯一突破口?
  3. Android简易聊天室软件(HTTP实现)
  4. oracle财务系统优劣势,ERP系统财务系统功能的优缺点分析对比
  5. SpringBoot集成海康威视Linux版本
  6. Excel 的进阶学习
  7. 【分享】测试小白如何测试手机整机系统测试
  8. AutoCAD 2019 汉化包
  9. 影子之美!太阳日照阴影变化之计算模拟
  10. Python爬虫实战 --实现 QQ空间自动点赞