Browse Source

comple adc_chassis. add adc_controller_shenlan_v2, near complete.

yuchuli 1 year ago
parent
commit
8288eeaf73

+ 1 - 0
src/ros2/src/adc_chassis/CMakeLists.txt

@@ -33,6 +33,7 @@ link_directories(
 
 add_executable(${PROJECT_NAME}
   src/adc_chassis_node.cpp
+  src/adc_chassis_core.cpp
 )
 
 ament_target_dependencies(${PROJECT_NAME} rclcpp std_msgs 

+ 47 - 0
src/ros2/src/adc_chassis/include/adc_chassis/adc_chassis_core.h

@@ -0,0 +1,47 @@
+
+
+#ifndef ADC_CHASSIS_CORE_H_
+#define ADC_CHASSIS_CORE_H_
+
+
+#include <rclcpp/rclcpp.hpp>
+
+
+#include "adc_autoware_msgs/msg/adc_can_frame.hpp"
+#include "adc_autoware_msgs/msg/adc_can_msgs.hpp"
+#include "adc_autoware_msgs/msg/adc_chassis.hpp"
+
+
+class adc_chassis_core : public rclcpp::Node
+{
+public:
+    adc_chassis_core();
+    ~adc_chassis_core() = default;
+
+private:
+
+
+
+private:
+    std::string simulated_frame_id_;  //!< @brief simulated vehicle frame id
+    std::string origin_frame_id_;     //!< @brief map frame_id
+    
+
+private:
+    
+    rclcpp::Publisher<adc_autoware_msgs::msg::AdcChassis>::SharedPtr pub_msgs_chassis;
+
+    rclcpp::Subscription<adc_autoware_msgs::msg::AdcCanMsgs>::SharedPtr sub_msgs_canrecv0;
+    rclcpp::Subscription<adc_autoware_msgs::msg::AdcCanMsgs>::SharedPtr sub_msgs_canrecv1;
+
+private:
+    void topic_canrecv0_callback(const adc_autoware_msgs::msg::AdcCanMsgs & msg) const;
+    void topic_canrecv1_callback(const adc_autoware_msgs::msg::AdcCanMsgs & msg) const;
+
+
+
+};
+
+
+
+#endif

+ 72 - 0
src/ros2/src/adc_chassis/src/adc_chassis_core.cpp

@@ -0,0 +1,72 @@
+#include "adc_chassis/adc_chassis_core.h"
+
+#include <functional>
+
+using  std::placeholders::_1;
+
+adc_chassis_core::adc_chassis_core(): Node("adc_chassis")
+{
+    sub_msgs_canrecv0 = this->create_subscription<adc_autoware_msgs::msg::AdcCanMsgs>("canrecv0",10,
+                            std::bind(&adc_chassis_core::topic_canrecv0_callback,this,_1));
+    sub_msgs_canrecv1 = this->create_subscription<adc_autoware_msgs::msg::AdcCanMsgs>("canrecv1",10,
+                            std::bind(&adc_chassis_core::topic_canrecv1_callback,this,_1));
+    pub_msgs_chassis = this->create_publisher<adc_autoware_msgs::msg::AdcChassis>("chassis",10);
+}
+
+
+void adc_chassis_core::topic_canrecv0_callback(const adc_autoware_msgs::msg::AdcCanMsgs & msg) const
+{
+    int i;
+    int ncount = static_cast<int>(msg.frames.size());
+    static bool bhavevel = false;
+    static bool bhaveang = false;
+    static double vehspeed = 0;
+    static double ang = 0;
+    for(i=0;i<ncount;i++)
+    {
+        unsigned char bytedata[64];
+
+        if(msg.frames[i].id == 0x1CC)
+        {
+            memcpy(bytedata,msg.frames[i].data.data(),64);
+            unsigned int value;
+            value = bytedata[12]&0x1F;
+            value = (value<<8) +  static_cast<unsigned int >( bytedata[13]);
+            vehspeed = static_cast<double>(value) * 0.05625;
+            bhavevel =  true;
+        }
+        if(msg.frames[i].id == 0x18a)
+        {
+            memcpy(bytedata,msg.frames[i].data.data(),64);
+            unsigned int value;
+            value = bytedata[0]&0xFF;
+            value = (value<<8) +  static_cast<unsigned int >( bytedata[1]);
+            if(value<32767)
+                ang = static_cast<double>(value) * 0.1;
+            else
+                ang=static_cast<double>(value) * 0.1-65536*0.1;
+            bhaveang = true;
+        }
+    }
+
+    if(bhaveang && bhavevel)
+    {
+        auto msgchassis = adc_autoware_msgs::msg::AdcChassis();
+        int64_t nnow = std::chrono::system_clock::now().time_since_epoch().count();
+        msgchassis.header.frame_id = "adc";
+        msgchassis.header.stamp.sec = nnow/1e9;
+        msgchassis.header.stamp.nanosec = nnow - msgchassis.header.stamp.sec * 1e9;
+        msgchassis.vel = vehspeed;
+        msgchassis.angle_feedback = ang;
+        pub_msgs_chassis->publish(msgchassis);
+        bhaveang = false;
+        bhavevel = false;
+    }
+
+    (void)msg;
+}
+
+void adc_chassis_core::topic_canrecv1_callback(const adc_autoware_msgs::msg::AdcCanMsgs & msg) const
+{
+    (void)msg;
+}

+ 2 - 1
src/ros2/src/adc_chassis/src/adc_chassis_node.cpp

@@ -1,6 +1,7 @@
 
 
 #include <rclcpp/rclcpp.hpp>
+#include "adc_chassis/adc_chassis_core.h"
 
 #include <memory>
 
@@ -8,7 +9,7 @@ int main(int argc, char ** argv)
 {
   rclcpp::init(argc, argv);
 
-//  rclcpp::spin(std::make_shared<adc_can_nvidia_agx>());
+  rclcpp::spin(std::make_shared<adc_chassis_core>());
   rclcpp::shutdown();
 
   return 0;

+ 59 - 0
src/ros2/src/adc_controller_shenlan_v2/CMakeLists.txt

@@ -0,0 +1,59 @@
+cmake_minimum_required(VERSION 3.8)
+project(adc_controller_shenlan_v2)
+
+if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
+  add_compile_options(-Wall -Wextra -Wpedantic)
+endif()
+
+# find dependencies
+find_package(ament_cmake REQUIRED)
+# uncomment the following section in order to fill in
+# further dependencies manually.
+# find_package(<dependency> REQUIRED)
+
+find_package(rclcpp REQUIRED)
+find_package(std_msgs REQUIRED)
+find_package(adc_autoware_msgs REQUIRED)
+find_package(autoware_auto_control_msgs REQUIRED)
+find_package(Protobuf REQUIRED)
+
+# uncomment the following section in order to fill in
+# further dependencies manually.
+# find_package(<dependency> REQUIRED)
+
+include_directories(
+##  INCLUDE_DIRS include
+  ${CMAKE_CURRENT_BINARY_DIR}/..
+  include
+  include/adc_controller_shenlan_v2
+)
+
+#message(ERROR "catkin_INCLUDE_DIRS: ${catkin_INCLUDE_DIRS}")
+#message(STATUS "CMAKE_CURRENT_BINARY_DIR: ${CMAKE_CURRENT_BINARY_DIR}")
+
+add_executable(${PROJECT_NAME}
+  src/adc_controller_shenlan_v2_node.cpp
+  src/adc_controller_shenlan_v2_core.cpp
+  src/control_status.cpp
+  src/controller.cpp
+  src/decition.pb.cc
+)
+
+target_link_libraries(${PROJECT_NAME}  ${Protobuf_LIBRARIES})  
+
+ament_target_dependencies(${PROJECT_NAME} rclcpp std_msgs 
+  adc_autoware_msgs autoware_auto_control_msgs)
+
+if(BUILD_TESTING)
+  find_package(ament_lint_auto REQUIRED)
+  # the following line skips the linter which checks for copyrights
+  # comment the line when a copyright and license is added to all source files
+  set(ament_cmake_copyright_FOUND TRUE)
+  # the following line skips cpplint (only works in a git repo)
+  # comment the line when this package is in a git repo and when
+  # a copyright and license is added to all source files
+  set(ament_cmake_cpplint_FOUND TRUE)
+  ament_lint_auto_find_test_dependencies()
+endif()
+
+ament_package()

+ 202 - 0
src/ros2/src/adc_controller_shenlan_v2/LICENSE

@@ -0,0 +1,202 @@
+
+                                 Apache License
+                           Version 2.0, January 2004
+                        http://www.apache.org/licenses/
+
+   TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION
+
+   1. Definitions.
+
+      "License" shall mean the terms and conditions for use, reproduction,
+      and distribution as defined by Sections 1 through 9 of this document.
+
+      "Licensor" shall mean the copyright owner or entity authorized by
+      the copyright owner that is granting the License.
+
+      "Legal Entity" shall mean the union of the acting entity and all
+      other entities that control, are controlled by, or are under common
+      control with that entity. For the purposes of this definition,
+      "control" means (i) the power, direct or indirect, to cause the
+      direction or management of such entity, whether by contract or
+      otherwise, or (ii) ownership of fifty percent (50%) or more of the
+      outstanding shares, or (iii) beneficial ownership of such entity.
+
+      "You" (or "Your") shall mean an individual or Legal Entity
+      exercising permissions granted by this License.
+
+      "Source" form shall mean the preferred form for making modifications,
+      including but not limited to software source code, documentation
+      source, and configuration files.
+
+      "Object" form shall mean any form resulting from mechanical
+      transformation or translation of a Source form, including but
+      not limited to compiled object code, generated documentation,
+      and conversions to other media types.
+
+      "Work" shall mean the work of authorship, whether in Source or
+      Object form, made available under the License, as indicated by a
+      copyright notice that is included in or attached to the work
+      (an example is provided in the Appendix below).
+
+      "Derivative Works" shall mean any work, whether in Source or Object
+      form, that is based on (or derived from) the Work and for which the
+      editorial revisions, annotations, elaborations, or other modifications
+      represent, as a whole, an original work of authorship. For the purposes
+      of this License, Derivative Works shall not include works that remain
+      separable from, or merely link (or bind by name) to the interfaces of,
+      the Work and Derivative Works thereof.
+
+      "Contribution" shall mean any work of authorship, including
+      the original version of the Work and any modifications or additions
+      to that Work or Derivative Works thereof, that is intentionally
+      submitted to Licensor for inclusion in the Work by the copyright owner
+      or by an individual or Legal Entity authorized to submit on behalf of
+      the copyright owner. For the purposes of this definition, "submitted"
+      means any form of electronic, verbal, or written communication sent
+      to the Licensor or its representatives, including but not limited to
+      communication on electronic mailing lists, source code control systems,
+      and issue tracking systems that are managed by, or on behalf of, the
+      Licensor for the purpose of discussing and improving the Work, but
+      excluding communication that is conspicuously marked or otherwise
+      designated in writing by the copyright owner as "Not a Contribution."
+
+      "Contributor" shall mean Licensor and any individual or Legal Entity
+      on behalf of whom a Contribution has been received by Licensor and
+      subsequently incorporated within the Work.
+
+   2. Grant of Copyright License. Subject to the terms and conditions of
+      this License, each Contributor hereby grants to You a perpetual,
+      worldwide, non-exclusive, no-charge, royalty-free, irrevocable
+      copyright license to reproduce, prepare Derivative Works of,
+      publicly display, publicly perform, sublicense, and distribute the
+      Work and such Derivative Works in Source or Object form.
+
+   3. Grant of Patent License. Subject to the terms and conditions of
+      this License, each Contributor hereby grants to You a perpetual,
+      worldwide, non-exclusive, no-charge, royalty-free, irrevocable
+      (except as stated in this section) patent license to make, have made,
+      use, offer to sell, sell, import, and otherwise transfer the Work,
+      where such license applies only to those patent claims licensable
+      by such Contributor that are necessarily infringed by their
+      Contribution(s) alone or by combination of their Contribution(s)
+      with the Work to which such Contribution(s) was submitted. If You
+      institute patent litigation against any entity (including a
+      cross-claim or counterclaim in a lawsuit) alleging that the Work
+      or a Contribution incorporated within the Work constitutes direct
+      or contributory patent infringement, then any patent licenses
+      granted to You under this License for that Work shall terminate
+      as of the date such litigation is filed.
+
+   4. Redistribution. You may reproduce and distribute copies of the
+      Work or Derivative Works thereof in any medium, with or without
+      modifications, and in Source or Object form, provided that You
+      meet the following conditions:
+
+      (a) You must give any other recipients of the Work or
+          Derivative Works a copy of this License; and
+
+      (b) You must cause any modified files to carry prominent notices
+          stating that You changed the files; and
+
+      (c) You must retain, in the Source form of any Derivative Works
+          that You distribute, all copyright, patent, trademark, and
+          attribution notices from the Source form of the Work,
+          excluding those notices that do not pertain to any part of
+          the Derivative Works; and
+
+      (d) If the Work includes a "NOTICE" text file as part of its
+          distribution, then any Derivative Works that You distribute must
+          include a readable copy of the attribution notices contained
+          within such NOTICE file, excluding those notices that do not
+          pertain to any part of the Derivative Works, in at least one
+          of the following places: within a NOTICE text file distributed
+          as part of the Derivative Works; within the Source form or
+          documentation, if provided along with the Derivative Works; or,
+          within a display generated by the Derivative Works, if and
+          wherever such third-party notices normally appear. The contents
+          of the NOTICE file are for informational purposes only and
+          do not modify the License. You may add Your own attribution
+          notices within Derivative Works that You distribute, alongside
+          or as an addendum to the NOTICE text from the Work, provided
+          that such additional attribution notices cannot be construed
+          as modifying the License.
+
+      You may add Your own copyright statement to Your modifications and
+      may provide additional or different license terms and conditions
+      for use, reproduction, or distribution of Your modifications, or
+      for any such Derivative Works as a whole, provided Your use,
+      reproduction, and distribution of the Work otherwise complies with
+      the conditions stated in this License.
+
+   5. Submission of Contributions. Unless You explicitly state otherwise,
+      any Contribution intentionally submitted for inclusion in the Work
+      by You to the Licensor shall be under the terms and conditions of
+      this License, without any additional terms or conditions.
+      Notwithstanding the above, nothing herein shall supersede or modify
+      the terms of any separate license agreement you may have executed
+      with Licensor regarding such Contributions.
+
+   6. Trademarks. This License does not grant permission to use the trade
+      names, trademarks, service marks, or product names of the Licensor,
+      except as required for reasonable and customary use in describing the
+      origin of the Work and reproducing the content of the NOTICE file.
+
+   7. Disclaimer of Warranty. Unless required by applicable law or
+      agreed to in writing, Licensor provides the Work (and each
+      Contributor provides its Contributions) on an "AS IS" BASIS,
+      WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or
+      implied, including, without limitation, any warranties or conditions
+      of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A
+      PARTICULAR PURPOSE. You are solely responsible for determining the
+      appropriateness of using or redistributing the Work and assume any
+      risks associated with Your exercise of permissions under this License.
+
+   8. Limitation of Liability. In no event and under no legal theory,
+      whether in tort (including negligence), contract, or otherwise,
+      unless required by applicable law (such as deliberate and grossly
+      negligent acts) or agreed to in writing, shall any Contributor be
+      liable to You for damages, including any direct, indirect, special,
+      incidental, or consequential damages of any character arising as a
+      result of this License or out of the use or inability to use the
+      Work (including but not limited to damages for loss of goodwill,
+      work stoppage, computer failure or malfunction, or any and all
+      other commercial damages or losses), even if such Contributor
+      has been advised of the possibility of such damages.
+
+   9. Accepting Warranty or Additional Liability. While redistributing
+      the Work or Derivative Works thereof, You may choose to offer,
+      and charge a fee for, acceptance of support, warranty, indemnity,
+      or other liability obligations and/or rights consistent with this
+      License. However, in accepting such obligations, You may act only
+      on Your own behalf and on Your sole responsibility, not on behalf
+      of any other Contributor, and only if You agree to indemnify,
+      defend, and hold each Contributor harmless for any liability
+      incurred by, or claims asserted against, such Contributor by reason
+      of your accepting any such warranty or additional liability.
+
+   END OF TERMS AND CONDITIONS
+
+   APPENDIX: How to apply the Apache License to your work.
+
+      To apply the Apache License to your work, attach the following
+      boilerplate notice, with the fields enclosed by brackets "[]"
+      replaced with your own identifying information. (Don't include
+      the brackets!)  The text should be enclosed in the appropriate
+      comment syntax for the file format. We also recommend that a
+      file or class name and description of purpose be included on the
+      same "printed page" as the copyright notice for easier
+      identification within third-party archives.
+
+   Copyright [yyyy] [name of copyright owner]
+
+   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.

+ 82 - 0
src/ros2/src/adc_controller_shenlan_v2/include/adc_controller_shenlan_v2/adc_controller_shenlan_v2_core.hpp

@@ -0,0 +1,82 @@
+
+#ifndef ADC_CONTROLLER_SHENLAN_V2_CORE_HPP_
+#define ADC_CONTROLLER_SHENLAN_V2_CORE_HPP_
+
+
+#include <rclcpp/rclcpp.hpp>
+
+#include <thread>
+#include <mutex>
+
+
+#include "adc_autoware_msgs/msg/adc_can_frame.hpp"
+#include "adc_autoware_msgs/msg/adc_can_msgs.hpp"
+#include "adc_autoware_msgs/msg/adc_chassis.hpp"
+#include "autoware_auto_control_msgs/msg/ackermann_control_command.hpp"
+
+#include "decition.pb.h"
+
+
+class adc_controller_shenlan_v2_core : public rclcpp::Node
+{
+public:
+    adc_controller_shenlan_v2_core();
+    ~adc_controller_shenlan_v2_core();
+
+private:
+
+
+
+private:
+    std::string simulated_frame_id_;  //!< @brief simulated vehicle frame id
+    std::string origin_frame_id_;     //!< @brief map frame_id
+    
+
+private:
+    
+    rclcpp::Subscription<adc_autoware_msgs::msg::AdcChassis>::SharedPtr sub_msgs_chassis;
+
+    rclcpp::Publisher<adc_autoware_msgs::msg::AdcCanMsgs>::SharedPtr pub_msgs_cansend0;
+
+    rclcpp::Subscription<autoware_auto_control_msgs::msg::AckermannControlCommand>::SharedPtr sub_msgs_cmd;
+
+private:
+    void topic_chassis_callback(const adc_autoware_msgs::msg::AdcChassis & msg);
+    void topic_cmd_callback(const autoware_auto_control_msgs::msg::AckermannControlCommand & msg) ;
+
+private:
+    void threadsend();
+    std::thread * mpthreadsend;
+    bool mbtheadrun = true;
+
+private:
+    void executeDecition(const iv::brain::decition &decition);
+    void ExecSend();
+    void Activate();
+    void UnAcitvate();
+    void initial();
+
+private:
+    bool gbHaveVehSpd = false;
+    double gfVehSpd = 0.0;
+
+    bool gbHaveWheelAngle = false;
+    double gfWheelAngle = 0.0;
+
+    iv::brain::decition gdecition_def;
+    iv::brain::decition gdecition;
+
+    int gnLastSendTime = 0;
+    int gnLastRecvDecTime = -1000;
+    int gnDecitionNum = 0; //when is zero,send default;
+    int gnDecitionNumMax = 100;
+    int gnIndex = 0;
+
+    double gfWheelSpeedLim = 300; //300 degrees per second
+    std::mutex gMutex;
+
+
+
+};
+
+#endif

+ 108 - 0
src/ros2/src/adc_controller_shenlan_v2/include/adc_controller_shenlan_v2/control_status.h

@@ -0,0 +1,108 @@
+#pragma once
+//由于控制器指令共享同一个ID 0x20,建立此类维护控制指令的最新状态
+
+//#include <boost.h>
+#include <cstdint>
+#include <boost/serialization/singleton.hpp>
+#include <adc_controller_shenlan_v2/vv7.h>
+
+namespace iv {
+namespace control {
+class ControlStatus : public boost::noncopyable
+{
+public:
+    /*****************
+             * ****测试标志位*****
+             * ***************/
+    int normal_speed  = 0;//常规速度
+    int swerve_speed  = 0;//转弯速度
+    int high_speed = 0;//快速
+    int mid_speed = 0;//中速
+    int low_speed = 0;//慢速
+    int change_line  = -1;//换道标志
+    int stop_obstacle = -1;//停障标志
+    int elude_obstacle = -1;//避障标志
+    int special_signle = -1;//特殊信号标志
+    int car_pullover = -1;//靠边停车标志位
+    float torque = 0.0;
+    float brake = 0.0;
+    float acc=0.0;
+
+    Command10 command10 ;
+    Command11 command11 ;
+    Command12 command12;
+    Command_Response command_reponse;
+
+    int command_ID10 = 0x10;
+    int command_ID11 = 0x11;
+    int command_ID12 = 0x12;
+
+
+    void set_wheel_angle(float angle);
+    void set_wheel_speed(float speed);
+    void set_wheel_enable(bool enable);
+
+
+
+
+
+    void set_speed_limit(float speed);
+    void set_torque(float percent);
+    void set_aeb(float aeb);
+    void set_brake(float brake);
+    void set_gear(int gear);
+    void set_handBrake(bool handBrake);
+    void set_driveMode(char mode);
+    void set_gear_enable(bool enable);
+    void set_aeb_enable(bool enable);
+    void set_acc_enable(bool enable);
+
+
+
+
+    void set_win_lf(char para);
+    void set_win_rf(char para);
+    void set_win_lr(char para);
+    void set_win_rr(char para);
+    void set_air_on(char para);
+    void set_air_cricle(char para);
+    void set_air_auto(char para);
+    void set_air_off(char para);
+    void set_air_temup(char para);
+    void set_air_temdown(char para);
+    void set_air_powerup(char para);
+    void set_air_powerdown(char para);
+    void set_obligate(char para);
+    void set_door(char enable);
+    void set_turnsignals_control(bool left, bool right);
+    void set_small_light(char para);
+    void set_near_light(char para);
+    void set_horn(char para);
+    void set_far_light(char para);
+    void set_frog_light(char para);
+    void set_wiper(char para);
+    void set_brake_light(char para);
+    void set_defrog(char para);
+    void set_reverse_light(char para);
+
+    void set_air_temp(char para);
+    void set_air_mode(char para);
+    void set_air_enable(bool enable);
+    void set_wind_level(char para);
+    void set_roof_light(char para);
+    void set_home_light(char para);
+    void set_air_worktime(char para);
+    void set_air_offtime(char para);
+
+    void set_cmd_checksum(unsigned char cmd_id);
+
+
+
+
+
+
+};
+typedef boost::serialization::singleton<iv::control::ControlStatus> ControlStatusSingleton;
+}
+}
+#define ServiceControlStatus iv::control::ControlStatusSingleton::get_mutable_instance()

+ 145 - 0
src/ros2/src/adc_controller_shenlan_v2/include/adc_controller_shenlan_v2/controlcan.h

@@ -0,0 +1,145 @@
+#ifndef CONTROLCAN1_H
+#define CONTROLCAN1_H
+
+
+#ifdef linux
+//接口卡类型定义
+#define VCI_PCI5121		1
+#define VCI_PCI9810		2
+#define VCI_USBCAN1		3
+#define VCI_USBCAN2		4
+#define VCI_PCI9820		5
+#define VCI_CAN232		6
+#define VCI_PCI5110		7
+#define VCI_CANLite		8
+#define VCI_ISA9620		9
+#define VCI_ISA5420		10
+
+//CAN错误码
+#define	ERR_CAN_OVERFLOW			0x0001	//CAN控制器内部FIFO溢出
+#define	ERR_CAN_ERRALARM			0x0002	//CAN控制器错误报警
+#define	ERR_CAN_PASSIVE				0x0004	//CAN控制器消极错误
+#define	ERR_CAN_LOSE				0x0008	//CAN控制器仲裁丢失
+#define	ERR_CAN_BUSERR				0x0010	//CAN控制器总线错误
+
+//通用错误码
+#define	ERR_DEVICEOPENED			0x0100	//设备已经打开
+#define	ERR_DEVICEOPEN				0x0200	//打开设备错误
+#define	ERR_DEVICENOTOPEN			0x0400	//设备没有打开
+#define	ERR_BUFFEROVERFLOW			0x0800	//缓冲区溢出
+#define	ERR_DEVICENOTEXIST			0x1000	//此设备不存在
+#define	ERR_LOADKERNELDLL			0x2000	//装载动态库失败
+#define ERR_CMDFAILED				0x4000	//执行命令失败错误码
+#define	ERR_BUFFERCREATE			0x8000	//内存不足
+
+
+//函数调用返回状态值
+#define	STATUS_OK					1
+#define STATUS_ERR					0
+	
+#define USHORT unsigned short int
+#define BYTE unsigned char
+#define CHAR char
+#define UCHAR unsigned char
+#define UINT unsigned int
+#define DWORD unsigned int
+#define PVOID void*
+#define ULONG unsigned int
+#define INT int
+#define UINT32 UINT
+#define LPVOID void*
+#define BOOL BYTE
+#define TRUE 1
+#define FALSE 0
+
+
+#if 1
+
+typedef  struct  _VCI_BOARD_INFO{//1.ZLGCAN系列接口卡信息的数据类型。
+		USHORT	hw_Version;
+		USHORT	fw_Version;
+		USHORT	dr_Version;
+		USHORT	in_Version;
+		USHORT	irq_Num;
+		BYTE	can_Num;
+		CHAR	str_Serial_Num[20];
+		CHAR	str_hw_Type[40];
+		USHORT	Reserved[4];
+} VCI_BOARD_INFO,*PVCI_BOARD_INFO; 
+
+
+typedef  struct  _VCI_CAN_OBJ{//2.定义CAN信息帧的数据类型。
+	UINT	ID;
+	UINT	TimeStamp;
+	BYTE	TimeFlag;
+	BYTE	SendType;
+	BYTE	RemoteFlag;//是否是远程帧
+	BYTE	ExternFlag;//是否是扩展帧
+	BYTE	DataLen;
+	BYTE	Data[8];
+	BYTE	Reserved[3];
+}VCI_CAN_OBJ,*PVCI_CAN_OBJ;
+
+
+typedef struct _VCI_CAN_STATUS{//3.定义CAN控制器状态的数据类型。
+	UCHAR	ErrInterrupt;
+	UCHAR	regMode;
+	UCHAR	regStatus;
+	UCHAR	regALCapture;
+	UCHAR	regECCapture; 
+	UCHAR	regEWLimit;
+	UCHAR	regRECounter; 
+	UCHAR	regTECounter;
+	DWORD	Reserved;
+}VCI_CAN_STATUS,*PVCI_CAN_STATUS;
+
+
+typedef struct _ERR_INFO{//4.定义错误信息的数据类型。
+		UINT	ErrCode;
+		BYTE	Passive_ErrData[3];
+		BYTE	ArLost_ErrData;
+} VCI_ERR_INFO,*PVCI_ERR_INFO;
+
+
+typedef struct _INIT_CONFIG{//5.定义初始化CAN的数据类型
+	DWORD	AccCode;
+	DWORD	AccMask;
+	DWORD	Reserved;
+	UCHAR	Filter;
+	UCHAR	Timing0;	
+	UCHAR	Timing1;	
+	UCHAR	Mode;
+}VCI_INIT_CONFIG,*PVCI_INIT_CONFIG;
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+DWORD VCI_OpenDevice(DWORD DeviceType,DWORD DeviceInd,DWORD Reserved);
+DWORD VCI_CloseDevice(DWORD DeviceType,DWORD DeviceInd);
+DWORD VCI_InitCAN(DWORD DeviceType, DWORD DeviceInd, DWORD CANInd, PVCI_INIT_CONFIG pInitConfig);
+
+DWORD VCI_ReadBoardInfo(DWORD DeviceType,DWORD DeviceInd,PVCI_BOARD_INFO pInfo);
+DWORD VCI_ReadErrInfo(DWORD DeviceType,DWORD DeviceInd,DWORD CANInd,PVCI_ERR_INFO pErrInfo);
+DWORD VCI_ReadCANStatus(DWORD DeviceType,DWORD DeviceInd,DWORD CANInd,PVCI_CAN_STATUS pCANStatus);
+
+DWORD VCI_GetReference(DWORD DeviceType,DWORD DeviceInd,DWORD CANInd,DWORD RefType,PVOID pData);
+DWORD VCI_SetReference(DWORD DeviceType,DWORD DeviceInd,DWORD CANInd,DWORD RefType,PVOID pData);
+
+ULONG VCI_GetReceiveNum(DWORD DeviceType,DWORD DeviceInd,DWORD CANInd);
+DWORD VCI_ClearBuffer(DWORD DeviceType,DWORD DeviceInd,DWORD CANInd);
+
+DWORD VCI_StartCAN(DWORD DeviceType,DWORD DeviceInd,DWORD CANInd);
+DWORD VCI_ResetCAN(DWORD DeviceType,DWORD DeviceInd,DWORD CANInd);
+
+ULONG VCI_Transmit(DWORD DeviceType,DWORD DeviceInd,DWORD CANInd,PVCI_CAN_OBJ pSend,UINT Len);
+ULONG VCI_Receive(DWORD DeviceType,DWORD DeviceInd,DWORD CANInd,PVCI_CAN_OBJ pReceive,UINT Len,INT WaitTime);
+
+#ifdef __cplusplus
+}
+#endif
+#endif
+
+#endif
+
+#endif

+ 83 - 0
src/ros2/src/adc_controller_shenlan_v2/include/adc_controller_shenlan_v2/controller.h

@@ -0,0 +1,83 @@
+#pragma once
+/*
+*控制器
+*/
+#ifndef _IV_CONTROL_CONTROLLER_
+#define _IV_CONTROL_CONTROLLER_
+
+//#include <boost.h>
+//#include <common/car_status.h>
+#include <adc_controller_shenlan_v2/control_status.h>
+
+namespace iv {
+    namespace control {
+        class Controller
+        {
+        public:
+            Controller();
+            ~Controller();
+            void inialize();// 初始化
+
+
+            void control_wheel(float angle);		//方向盘控制
+            void control_angle_speed(float angSpeed);
+            void control_angle_enable(bool enable);
+
+            void control_speed_limit(float speedLimit);
+            void control_torque(float percent);	//油门开度控制
+            void control_aeb(float aeb);	//油门开度控制
+            void control_brake(float brake);
+            void control_gear(float gear);
+            void control_handBrake(bool  enable);
+            void control_mode(char mode);
+            void control_gear_en(bool enable);
+            void control_aeb_en(bool enable);
+            void control_acc_en(bool enanble);
+
+
+            void control_win_lf(char para);
+            void control_win_rf(char para);
+            void control_win_lr(char para);
+            void control_win_rr(char para);
+            void control_air_on(bool enable);
+            void control_air_cricle(char para);
+            void control_air_auto(char para);
+            void control_air_off(char para);
+            void control_air_temup(char para);
+            void control_air_temdown(char para);
+            void control_air_powerup(char para);
+            void control_air_powerdown(char para);
+            void control_obligate(char para);
+            void control_door(char enable);
+            void control_turnsignals(bool left, bool right);
+            void control_small_light(char para);
+            void control_near_light(char para);
+            void control_horn(char para);
+            void control_far_light(char para);
+            void control_frog_light(char para);
+            void control_wiper(char para);
+            void control_brake_light(char para);
+            void control_defrog(char para);
+            void control_reverse_light(char para);
+            void cmd_checksum(unsigned char cmd_id);
+
+
+
+            void control_air_temp(char para);
+            void control_air_mode(char para);
+            void control_air_enable(bool enable);
+            void control_wind_level(char para);
+            void control_roof_light(char para);
+            void control_home_light(char para);
+            void control_air_worktime(char para);
+            void control_air_offtime(char para);
+
+            ///* 获取当前车辆状态*/
+            //void getCurrentCarStatus(iv::CarStatus & car_status);
+
+        private:
+        };
+    }
+}
+
+#endif // !_IV_CONTROL_CONTROLLER_

+ 2420 - 0
src/ros2/src/adc_controller_shenlan_v2/include/adc_controller_shenlan_v2/decition.pb.h

@@ -0,0 +1,2420 @@
+// Generated by the protocol buffer compiler.  DO NOT EDIT!
+// source: decition.proto
+
+#ifndef GOOGLE_PROTOBUF_INCLUDED_decition_2eproto
+#define GOOGLE_PROTOBUF_INCLUDED_decition_2eproto
+
+#include <limits>
+#include <string>
+
+#include <google/protobuf/port_def.inc>
+#if PROTOBUF_VERSION < 3012000
+#error This file was generated by a newer version of protoc which is
+#error incompatible with your Protocol Buffer headers. Please update
+#error your headers.
+#endif
+#if 3012004 < PROTOBUF_MIN_PROTOC_VERSION
+#error This file was generated by an older version of protoc which is
+#error incompatible with your Protocol Buffer headers. Please
+#error regenerate this file with a newer version of protoc.
+#endif
+
+#include <google/protobuf/port_undef.inc>
+#include <google/protobuf/io/coded_stream.h>
+#include <google/protobuf/arena.h>
+#include <google/protobuf/arenastring.h>
+#include <google/protobuf/generated_message_table_driven.h>
+#include <google/protobuf/generated_message_util.h>
+#include <google/protobuf/inlined_string_field.h>
+#include <google/protobuf/metadata_lite.h>
+#include <google/protobuf/generated_message_reflection.h>
+#include <google/protobuf/message.h>
+#include <google/protobuf/repeated_field.h>  // IWYU pragma: export
+#include <google/protobuf/extension_set.h>  // IWYU pragma: export
+#include <google/protobuf/unknown_field_set.h>
+// @@protoc_insertion_point(includes)
+#include <google/protobuf/port_def.inc>
+#define PROTOBUF_INTERNAL_EXPORT_decition_2eproto
+PROTOBUF_NAMESPACE_OPEN
+namespace internal {
+class AnyMetadata;
+}  // namespace internal
+PROTOBUF_NAMESPACE_CLOSE
+
+// Internal implementation detail -- do not use these members.
+struct TableStruct_decition_2eproto {
+  static const ::PROTOBUF_NAMESPACE_ID::internal::ParseTableField entries[]
+    PROTOBUF_SECTION_VARIABLE(protodesc_cold);
+  static const ::PROTOBUF_NAMESPACE_ID::internal::AuxillaryParseTableField aux[]
+    PROTOBUF_SECTION_VARIABLE(protodesc_cold);
+  static const ::PROTOBUF_NAMESPACE_ID::internal::ParseTable schema[1]
+    PROTOBUF_SECTION_VARIABLE(protodesc_cold);
+  static const ::PROTOBUF_NAMESPACE_ID::internal::FieldMetadata field_metadata[];
+  static const ::PROTOBUF_NAMESPACE_ID::internal::SerializationTable serialization_table[];
+  static const ::PROTOBUF_NAMESPACE_ID::uint32 offsets[];
+};
+extern const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable descriptor_table_decition_2eproto;
+namespace iv {
+namespace brain {
+class decition;
+class decitionDefaultTypeInternal;
+extern decitionDefaultTypeInternal _decition_default_instance_;
+}  // namespace brain
+}  // namespace iv
+PROTOBUF_NAMESPACE_OPEN
+template<> ::iv::brain::decition* Arena::CreateMaybeMessage<::iv::brain::decition>(Arena*);
+PROTOBUF_NAMESPACE_CLOSE
+namespace iv {
+namespace brain {
+
+// ===================================================================
+
+class decition PROTOBUF_FINAL :
+    public ::PROTOBUF_NAMESPACE_ID::Message /* @@protoc_insertion_point(class_definition:iv.brain.decition) */ {
+ public:
+  inline decition() : decition(nullptr) {};
+  virtual ~decition();
+
+  decition(const decition& from);
+  decition(decition&& from) noexcept
+    : decition() {
+    *this = ::std::move(from);
+  }
+
+  inline decition& operator=(const decition& from) {
+    CopyFrom(from);
+    return *this;
+  }
+  inline decition& operator=(decition&& from) noexcept {
+    if (GetArena() == from.GetArena()) {
+      if (this != &from) InternalSwap(&from);
+    } else {
+      CopyFrom(from);
+    }
+    return *this;
+  }
+
+  inline const ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet& unknown_fields() const {
+    return _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance);
+  }
+  inline ::PROTOBUF_NAMESPACE_ID::UnknownFieldSet* mutable_unknown_fields() {
+    return _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>();
+  }
+
+  static const ::PROTOBUF_NAMESPACE_ID::Descriptor* descriptor() {
+    return GetDescriptor();
+  }
+  static const ::PROTOBUF_NAMESPACE_ID::Descriptor* GetDescriptor() {
+    return GetMetadataStatic().descriptor;
+  }
+  static const ::PROTOBUF_NAMESPACE_ID::Reflection* GetReflection() {
+    return GetMetadataStatic().reflection;
+  }
+  static const decition& default_instance();
+
+  static void InitAsDefaultInstance();  // FOR INTERNAL USE ONLY
+  static inline const decition* internal_default_instance() {
+    return reinterpret_cast<const decition*>(
+               &_decition_default_instance_);
+  }
+  static constexpr int kIndexInFileMessages =
+    0;
+
+  friend void swap(decition& a, decition& b) {
+    a.Swap(&b);
+  }
+  inline void Swap(decition* other) {
+    if (other == this) return;
+    if (GetArena() == other->GetArena()) {
+      InternalSwap(other);
+    } else {
+      ::PROTOBUF_NAMESPACE_ID::internal::GenericSwap(this, other);
+    }
+  }
+  void UnsafeArenaSwap(decition* other) {
+    if (other == this) return;
+    GOOGLE_DCHECK(GetArena() == other->GetArena());
+    InternalSwap(other);
+  }
+
+  // implements Message ----------------------------------------------
+
+  inline decition* New() const final {
+    return CreateMaybeMessage<decition>(nullptr);
+  }
+
+  decition* New(::PROTOBUF_NAMESPACE_ID::Arena* arena) const final {
+    return CreateMaybeMessage<decition>(arena);
+  }
+  void CopyFrom(const ::PROTOBUF_NAMESPACE_ID::Message& from) final;
+  void MergeFrom(const ::PROTOBUF_NAMESPACE_ID::Message& from) final;
+  void CopyFrom(const decition& from);
+  void MergeFrom(const decition& from);
+  PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final;
+  bool IsInitialized() const final;
+
+  size_t ByteSizeLong() const final;
+  const char* _InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) final;
+  ::PROTOBUF_NAMESPACE_ID::uint8* _InternalSerialize(
+      ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const final;
+  int GetCachedSize() const final { return _cached_size_.Get(); }
+
+  private:
+  inline void SharedCtor();
+  inline void SharedDtor();
+  void SetCachedSize(int size) const final;
+  void InternalSwap(decition* other);
+  friend class ::PROTOBUF_NAMESPACE_ID::internal::AnyMetadata;
+  static ::PROTOBUF_NAMESPACE_ID::StringPiece FullMessageName() {
+    return "iv.brain.decition";
+  }
+  protected:
+  explicit decition(::PROTOBUF_NAMESPACE_ID::Arena* arena);
+  private:
+  static void ArenaDtor(void* object);
+  inline void RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena* arena);
+  public:
+
+  ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadata() const final;
+  private:
+  static ::PROTOBUF_NAMESPACE_ID::Metadata GetMetadataStatic() {
+    ::PROTOBUF_NAMESPACE_ID::internal::AssignDescriptors(&::descriptor_table_decition_2eproto);
+    return ::descriptor_table_decition_2eproto.file_level_metadata[kIndexInFileMessages];
+  }
+
+  public:
+
+  // nested types ----------------------------------------------------
+
+  // accessors -------------------------------------------------------
+
+  enum : int {
+    kSpeedFieldNumber = 1,
+    kWheelAngleFieldNumber = 2,
+    kWheelSpeedFieldNumber = 3,
+    kLateralTorqueFieldNumber = 4,
+    kBrakeFieldNumber = 5,
+    kAcceleratorFieldNumber = 6,
+    kTorqueFieldNumber = 7,
+    kLeftLampFieldNumber = 8,
+    kRightLampFieldNumber = 9,
+    kDoubleSparkFieldNumber = 10,
+    kHeadLightFieldNumber = 11,
+    kDippedLightFieldNumber = 13,
+    kHighBeamFieldNumber = 12,
+    kTailLightFieldNumber = 14,
+    kDomeLightFieldNumber = 15,
+    kFogLampFieldNumber = 16,
+    kEngineFieldNumber = 19,
+    kModeFieldNumber = 20,
+    kHandBrakeFieldNumber = 21,
+    kBackupLightFieldNumber = 17,
+    kBrakeLampFieldNumber = 18,
+    kSpeakFieldNumber = 22,
+    kAirEnableFieldNumber = 28,
+    kDoorFieldNumber = 23,
+    kGearFieldNumber = 24,
+    kWiperFieldNumber = 25,
+    kGradeFieldNumber = 26,
+    kTtcFieldNumber = 27,
+    kAirTempFieldNumber = 29,
+    kAirModeFieldNumber = 30,
+    kWindLevelFieldNumber = 31,
+    kRoofLightFieldNumber = 32,
+    kHomeLightFieldNumber = 33,
+    kAirWorktimeFieldNumber = 34,
+    kAirOfftimeFieldNumber = 35,
+    kAirOnFieldNumber = 36,
+    kAirAcFieldNumber = 37,
+    kAirCircleFieldNumber = 38,
+    kAirAutoFieldNumber = 39,
+    kAirOffFieldNumber = 40,
+    kWindowFlFieldNumber = 41,
+    kWindowFrFieldNumber = 42,
+    kWindowRlFieldNumber = 43,
+    kWindowRrFieldNumber = 44,
+    kAngleModeFieldNumber = 45,
+    kAngleActiveFieldNumber = 46,
+    kAccActiveFieldNumber = 47,
+    kBrakeActiveFieldNumber = 48,
+    kBrakeTypeFieldNumber = 49,
+    kNiujuYFieldNumber = 50,
+    kAutoModeFieldNumber = 51,
+  };
+  // optional float speed = 1;
+  bool has_speed() const;
+  private:
+  bool _internal_has_speed() const;
+  public:
+  void clear_speed();
+  float speed() const;
+  void set_speed(float value);
+  private:
+  float _internal_speed() const;
+  void _internal_set_speed(float value);
+  public:
+
+  // optional float wheelAngle = 2;
+  bool has_wheelangle() const;
+  private:
+  bool _internal_has_wheelangle() const;
+  public:
+  void clear_wheelangle();
+  float wheelangle() const;
+  void set_wheelangle(float value);
+  private:
+  float _internal_wheelangle() const;
+  void _internal_set_wheelangle(float value);
+  public:
+
+  // optional float wheelSpeed = 3;
+  bool has_wheelspeed() const;
+  private:
+  bool _internal_has_wheelspeed() const;
+  public:
+  void clear_wheelspeed();
+  float wheelspeed() const;
+  void set_wheelspeed(float value);
+  private:
+  float _internal_wheelspeed() const;
+  void _internal_set_wheelspeed(float value);
+  public:
+
+  // optional float lateralTorque = 4;
+  bool has_lateraltorque() const;
+  private:
+  bool _internal_has_lateraltorque() const;
+  public:
+  void clear_lateraltorque();
+  float lateraltorque() const;
+  void set_lateraltorque(float value);
+  private:
+  float _internal_lateraltorque() const;
+  void _internal_set_lateraltorque(float value);
+  public:
+
+  // optional float brake = 5;
+  bool has_brake() const;
+  private:
+  bool _internal_has_brake() const;
+  public:
+  void clear_brake();
+  float brake() const;
+  void set_brake(float value);
+  private:
+  float _internal_brake() const;
+  void _internal_set_brake(float value);
+  public:
+
+  // optional float accelerator = 6;
+  bool has_accelerator() const;
+  private:
+  bool _internal_has_accelerator() const;
+  public:
+  void clear_accelerator();
+  float accelerator() const;
+  void set_accelerator(float value);
+  private:
+  float _internal_accelerator() const;
+  void _internal_set_accelerator(float value);
+  public:
+
+  // optional float torque = 7;
+  bool has_torque() const;
+  private:
+  bool _internal_has_torque() const;
+  public:
+  void clear_torque();
+  float torque() const;
+  void set_torque(float value);
+  private:
+  float _internal_torque() const;
+  void _internal_set_torque(float value);
+  public:
+
+  // optional bool leftLamp = 8;
+  bool has_leftlamp() const;
+  private:
+  bool _internal_has_leftlamp() const;
+  public:
+  void clear_leftlamp();
+  bool leftlamp() const;
+  void set_leftlamp(bool value);
+  private:
+  bool _internal_leftlamp() const;
+  void _internal_set_leftlamp(bool value);
+  public:
+
+  // optional bool rightLamp = 9;
+  bool has_rightlamp() const;
+  private:
+  bool _internal_has_rightlamp() const;
+  public:
+  void clear_rightlamp();
+  bool rightlamp() const;
+  void set_rightlamp(bool value);
+  private:
+  bool _internal_rightlamp() const;
+  void _internal_set_rightlamp(bool value);
+  public:
+
+  // optional bool doubleSpark = 10;
+  bool has_doublespark() const;
+  private:
+  bool _internal_has_doublespark() const;
+  public:
+  void clear_doublespark();
+  bool doublespark() const;
+  void set_doublespark(bool value);
+  private:
+  bool _internal_doublespark() const;
+  void _internal_set_doublespark(bool value);
+  public:
+
+  // optional bool headLight = 11;
+  bool has_headlight() const;
+  private:
+  bool _internal_has_headlight() const;
+  public:
+  void clear_headlight();
+  bool headlight() const;
+  void set_headlight(bool value);
+  private:
+  bool _internal_headlight() const;
+  void _internal_set_headlight(bool value);
+  public:
+
+  // optional int32 dippedLight = 13;
+  bool has_dippedlight() const;
+  private:
+  bool _internal_has_dippedlight() const;
+  public:
+  void clear_dippedlight();
+  ::PROTOBUF_NAMESPACE_ID::int32 dippedlight() const;
+  void set_dippedlight(::PROTOBUF_NAMESPACE_ID::int32 value);
+  private:
+  ::PROTOBUF_NAMESPACE_ID::int32 _internal_dippedlight() const;
+  void _internal_set_dippedlight(::PROTOBUF_NAMESPACE_ID::int32 value);
+  public:
+
+  // optional bool highBeam = 12;
+  bool has_highbeam() const;
+  private:
+  bool _internal_has_highbeam() const;
+  public:
+  void clear_highbeam();
+  bool highbeam() const;
+  void set_highbeam(bool value);
+  private:
+  bool _internal_highbeam() const;
+  void _internal_set_highbeam(bool value);
+  public:
+
+  // optional bool tailLight = 14;
+  bool has_taillight() const;
+  private:
+  bool _internal_has_taillight() const;
+  public:
+  void clear_taillight();
+  bool taillight() const;
+  void set_taillight(bool value);
+  private:
+  bool _internal_taillight() const;
+  void _internal_set_taillight(bool value);
+  public:
+
+  // optional bool domeLight = 15;
+  bool has_domelight() const;
+  private:
+  bool _internal_has_domelight() const;
+  public:
+  void clear_domelight();
+  bool domelight() const;
+  void set_domelight(bool value);
+  private:
+  bool _internal_domelight() const;
+  void _internal_set_domelight(bool value);
+  public:
+
+  // optional bool fogLamp = 16;
+  bool has_foglamp() const;
+  private:
+  bool _internal_has_foglamp() const;
+  public:
+  void clear_foglamp();
+  bool foglamp() const;
+  void set_foglamp(bool value);
+  private:
+  bool _internal_foglamp() const;
+  void _internal_set_foglamp(bool value);
+  public:
+
+  // optional int32 engine = 19;
+  bool has_engine() const;
+  private:
+  bool _internal_has_engine() const;
+  public:
+  void clear_engine();
+  ::PROTOBUF_NAMESPACE_ID::int32 engine() const;
+  void set_engine(::PROTOBUF_NAMESPACE_ID::int32 value);
+  private:
+  ::PROTOBUF_NAMESPACE_ID::int32 _internal_engine() const;
+  void _internal_set_engine(::PROTOBUF_NAMESPACE_ID::int32 value);
+  public:
+
+  // optional int32 mode = 20;
+  bool has_mode() const;
+  private:
+  bool _internal_has_mode() const;
+  public:
+  void clear_mode();
+  ::PROTOBUF_NAMESPACE_ID::int32 mode() const;
+  void set_mode(::PROTOBUF_NAMESPACE_ID::int32 value);
+  private:
+  ::PROTOBUF_NAMESPACE_ID::int32 _internal_mode() const;
+  void _internal_set_mode(::PROTOBUF_NAMESPACE_ID::int32 value);
+  public:
+
+  // optional int32 handBrake = 21;
+  bool has_handbrake() const;
+  private:
+  bool _internal_has_handbrake() const;
+  public:
+  void clear_handbrake();
+  ::PROTOBUF_NAMESPACE_ID::int32 handbrake() const;
+  void set_handbrake(::PROTOBUF_NAMESPACE_ID::int32 value);
+  private:
+  ::PROTOBUF_NAMESPACE_ID::int32 _internal_handbrake() const;
+  void _internal_set_handbrake(::PROTOBUF_NAMESPACE_ID::int32 value);
+  public:
+
+  // optional bool backupLight = 17;
+  bool has_backuplight() const;
+  private:
+  bool _internal_has_backuplight() const;
+  public:
+  void clear_backuplight();
+  bool backuplight() const;
+  void set_backuplight(bool value);
+  private:
+  bool _internal_backuplight() const;
+  void _internal_set_backuplight(bool value);
+  public:
+
+  // optional bool brakeLamp = 18;
+  bool has_brakelamp() const;
+  private:
+  bool _internal_has_brakelamp() const;
+  public:
+  void clear_brakelamp();
+  bool brakelamp() const;
+  void set_brakelamp(bool value);
+  private:
+  bool _internal_brakelamp() const;
+  void _internal_set_brakelamp(bool value);
+  public:
+
+  // optional bool speak = 22;
+  bool has_speak() const;
+  private:
+  bool _internal_has_speak() const;
+  public:
+  void clear_speak();
+  bool speak() const;
+  void set_speak(bool value);
+  private:
+  bool _internal_speak() const;
+  void _internal_set_speak(bool value);
+  public:
+
+  // optional bool air_enable = 28;
+  bool has_air_enable() const;
+  private:
+  bool _internal_has_air_enable() const;
+  public:
+  void clear_air_enable();
+  bool air_enable() const;
+  void set_air_enable(bool value);
+  private:
+  bool _internal_air_enable() const;
+  void _internal_set_air_enable(bool value);
+  public:
+
+  // optional int32 door = 23;
+  bool has_door() const;
+  private:
+  bool _internal_has_door() const;
+  public:
+  void clear_door();
+  ::PROTOBUF_NAMESPACE_ID::int32 door() const;
+  void set_door(::PROTOBUF_NAMESPACE_ID::int32 value);
+  private:
+  ::PROTOBUF_NAMESPACE_ID::int32 _internal_door() const;
+  void _internal_set_door(::PROTOBUF_NAMESPACE_ID::int32 value);
+  public:
+
+  // optional int32 gear = 24;
+  bool has_gear() const;
+  private:
+  bool _internal_has_gear() const;
+  public:
+  void clear_gear();
+  ::PROTOBUF_NAMESPACE_ID::int32 gear() const;
+  void set_gear(::PROTOBUF_NAMESPACE_ID::int32 value);
+  private:
+  ::PROTOBUF_NAMESPACE_ID::int32 _internal_gear() const;
+  void _internal_set_gear(::PROTOBUF_NAMESPACE_ID::int32 value);
+  public:
+
+  // optional int32 wiper = 25;
+  bool has_wiper() const;
+  private:
+  bool _internal_has_wiper() const;
+  public:
+  void clear_wiper();
+  ::PROTOBUF_NAMESPACE_ID::int32 wiper() const;
+  void set_wiper(::PROTOBUF_NAMESPACE_ID::int32 value);
+  private:
+  ::PROTOBUF_NAMESPACE_ID::int32 _internal_wiper() const;
+  void _internal_set_wiper(::PROTOBUF_NAMESPACE_ID::int32 value);
+  public:
+
+  // optional int32 grade = 26;
+  bool has_grade() const;
+  private:
+  bool _internal_has_grade() const;
+  public:
+  void clear_grade();
+  ::PROTOBUF_NAMESPACE_ID::int32 grade() const;
+  void set_grade(::PROTOBUF_NAMESPACE_ID::int32 value);
+  private:
+  ::PROTOBUF_NAMESPACE_ID::int32 _internal_grade() const;
+  void _internal_set_grade(::PROTOBUF_NAMESPACE_ID::int32 value);
+  public:
+
+  // optional float ttc = 27;
+  bool has_ttc() const;
+  private:
+  bool _internal_has_ttc() const;
+  public:
+  void clear_ttc();
+  float ttc() const;
+  void set_ttc(float value);
+  private:
+  float _internal_ttc() const;
+  void _internal_set_ttc(float value);
+  public:
+
+  // optional float air_temp = 29;
+  bool has_air_temp() const;
+  private:
+  bool _internal_has_air_temp() const;
+  public:
+  void clear_air_temp();
+  float air_temp() const;
+  void set_air_temp(float value);
+  private:
+  float _internal_air_temp() const;
+  void _internal_set_air_temp(float value);
+  public:
+
+  // optional float air_mode = 30;
+  bool has_air_mode() const;
+  private:
+  bool _internal_has_air_mode() const;
+  public:
+  void clear_air_mode();
+  float air_mode() const;
+  void set_air_mode(float value);
+  private:
+  float _internal_air_mode() const;
+  void _internal_set_air_mode(float value);
+  public:
+
+  // optional float wind_level = 31;
+  bool has_wind_level() const;
+  private:
+  bool _internal_has_wind_level() const;
+  public:
+  void clear_wind_level();
+  float wind_level() const;
+  void set_wind_level(float value);
+  private:
+  float _internal_wind_level() const;
+  void _internal_set_wind_level(float value);
+  public:
+
+  // optional int32 roof_light = 32;
+  bool has_roof_light() const;
+  private:
+  bool _internal_has_roof_light() const;
+  public:
+  void clear_roof_light();
+  ::PROTOBUF_NAMESPACE_ID::int32 roof_light() const;
+  void set_roof_light(::PROTOBUF_NAMESPACE_ID::int32 value);
+  private:
+  ::PROTOBUF_NAMESPACE_ID::int32 _internal_roof_light() const;
+  void _internal_set_roof_light(::PROTOBUF_NAMESPACE_ID::int32 value);
+  public:
+
+  // optional int32 home_light = 33;
+  bool has_home_light() const;
+  private:
+  bool _internal_has_home_light() const;
+  public:
+  void clear_home_light();
+  ::PROTOBUF_NAMESPACE_ID::int32 home_light() const;
+  void set_home_light(::PROTOBUF_NAMESPACE_ID::int32 value);
+  private:
+  ::PROTOBUF_NAMESPACE_ID::int32 _internal_home_light() const;
+  void _internal_set_home_light(::PROTOBUF_NAMESPACE_ID::int32 value);
+  public:
+
+  // optional float air_worktime = 34;
+  bool has_air_worktime() const;
+  private:
+  bool _internal_has_air_worktime() const;
+  public:
+  void clear_air_worktime();
+  float air_worktime() const;
+  void set_air_worktime(float value);
+  private:
+  float _internal_air_worktime() const;
+  void _internal_set_air_worktime(float value);
+  public:
+
+  // optional float air_offtime = 35;
+  bool has_air_offtime() const;
+  private:
+  bool _internal_has_air_offtime() const;
+  public:
+  void clear_air_offtime();
+  float air_offtime() const;
+  void set_air_offtime(float value);
+  private:
+  float _internal_air_offtime() const;
+  void _internal_set_air_offtime(float value);
+  public:
+
+  // optional bool air_on = 36;
+  bool has_air_on() const;
+  private:
+  bool _internal_has_air_on() const;
+  public:
+  void clear_air_on();
+  bool air_on() const;
+  void set_air_on(bool value);
+  private:
+  bool _internal_air_on() const;
+  void _internal_set_air_on(bool value);
+  public:
+
+  // optional bool air_ac = 37;
+  bool has_air_ac() const;
+  private:
+  bool _internal_has_air_ac() const;
+  public:
+  void clear_air_ac();
+  bool air_ac() const;
+  void set_air_ac(bool value);
+  private:
+  bool _internal_air_ac() const;
+  void _internal_set_air_ac(bool value);
+  public:
+
+  // optional bool air_circle = 38;
+  bool has_air_circle() const;
+  private:
+  bool _internal_has_air_circle() const;
+  public:
+  void clear_air_circle();
+  bool air_circle() const;
+  void set_air_circle(bool value);
+  private:
+  bool _internal_air_circle() const;
+  void _internal_set_air_circle(bool value);
+  public:
+
+  // optional bool air_auto = 39;
+  bool has_air_auto() const;
+  private:
+  bool _internal_has_air_auto() const;
+  public:
+  void clear_air_auto();
+  bool air_auto() const;
+  void set_air_auto(bool value);
+  private:
+  bool _internal_air_auto() const;
+  void _internal_set_air_auto(bool value);
+  public:
+
+  // optional bool air_off = 40;
+  bool has_air_off() const;
+  private:
+  bool _internal_has_air_off() const;
+  public:
+  void clear_air_off();
+  bool air_off() const;
+  void set_air_off(bool value);
+  private:
+  bool _internal_air_off() const;
+  void _internal_set_air_off(bool value);
+  public:
+
+  // optional uint32 window_fl = 41;
+  bool has_window_fl() const;
+  private:
+  bool _internal_has_window_fl() const;
+  public:
+  void clear_window_fl();
+  ::PROTOBUF_NAMESPACE_ID::uint32 window_fl() const;
+  void set_window_fl(::PROTOBUF_NAMESPACE_ID::uint32 value);
+  private:
+  ::PROTOBUF_NAMESPACE_ID::uint32 _internal_window_fl() const;
+  void _internal_set_window_fl(::PROTOBUF_NAMESPACE_ID::uint32 value);
+  public:
+
+  // optional uint32 window_fr = 42;
+  bool has_window_fr() const;
+  private:
+  bool _internal_has_window_fr() const;
+  public:
+  void clear_window_fr();
+  ::PROTOBUF_NAMESPACE_ID::uint32 window_fr() const;
+  void set_window_fr(::PROTOBUF_NAMESPACE_ID::uint32 value);
+  private:
+  ::PROTOBUF_NAMESPACE_ID::uint32 _internal_window_fr() const;
+  void _internal_set_window_fr(::PROTOBUF_NAMESPACE_ID::uint32 value);
+  public:
+
+  // optional uint32 window_rl = 43;
+  bool has_window_rl() const;
+  private:
+  bool _internal_has_window_rl() const;
+  public:
+  void clear_window_rl();
+  ::PROTOBUF_NAMESPACE_ID::uint32 window_rl() const;
+  void set_window_rl(::PROTOBUF_NAMESPACE_ID::uint32 value);
+  private:
+  ::PROTOBUF_NAMESPACE_ID::uint32 _internal_window_rl() const;
+  void _internal_set_window_rl(::PROTOBUF_NAMESPACE_ID::uint32 value);
+  public:
+
+  // optional uint32 window_rr = 44;
+  bool has_window_rr() const;
+  private:
+  bool _internal_has_window_rr() const;
+  public:
+  void clear_window_rr();
+  ::PROTOBUF_NAMESPACE_ID::uint32 window_rr() const;
+  void set_window_rr(::PROTOBUF_NAMESPACE_ID::uint32 value);
+  private:
+  ::PROTOBUF_NAMESPACE_ID::uint32 _internal_window_rr() const;
+  void _internal_set_window_rr(::PROTOBUF_NAMESPACE_ID::uint32 value);
+  public:
+
+  // optional uint32 angle_mode = 45;
+  bool has_angle_mode() const;
+  private:
+  bool _internal_has_angle_mode() const;
+  public:
+  void clear_angle_mode();
+  ::PROTOBUF_NAMESPACE_ID::uint32 angle_mode() const;
+  void set_angle_mode(::PROTOBUF_NAMESPACE_ID::uint32 value);
+  private:
+  ::PROTOBUF_NAMESPACE_ID::uint32 _internal_angle_mode() const;
+  void _internal_set_angle_mode(::PROTOBUF_NAMESPACE_ID::uint32 value);
+  public:
+
+  // optional uint32 angle_active = 46;
+  bool has_angle_active() const;
+  private:
+  bool _internal_has_angle_active() const;
+  public:
+  void clear_angle_active();
+  ::PROTOBUF_NAMESPACE_ID::uint32 angle_active() const;
+  void set_angle_active(::PROTOBUF_NAMESPACE_ID::uint32 value);
+  private:
+  ::PROTOBUF_NAMESPACE_ID::uint32 _internal_angle_active() const;
+  void _internal_set_angle_active(::PROTOBUF_NAMESPACE_ID::uint32 value);
+  public:
+
+  // optional uint32 acc_active = 47;
+  bool has_acc_active() const;
+  private:
+  bool _internal_has_acc_active() const;
+  public:
+  void clear_acc_active();
+  ::PROTOBUF_NAMESPACE_ID::uint32 acc_active() const;
+  void set_acc_active(::PROTOBUF_NAMESPACE_ID::uint32 value);
+  private:
+  ::PROTOBUF_NAMESPACE_ID::uint32 _internal_acc_active() const;
+  void _internal_set_acc_active(::PROTOBUF_NAMESPACE_ID::uint32 value);
+  public:
+
+  // optional uint32 brake_active = 48;
+  bool has_brake_active() const;
+  private:
+  bool _internal_has_brake_active() const;
+  public:
+  void clear_brake_active();
+  ::PROTOBUF_NAMESPACE_ID::uint32 brake_active() const;
+  void set_brake_active(::PROTOBUF_NAMESPACE_ID::uint32 value);
+  private:
+  ::PROTOBUF_NAMESPACE_ID::uint32 _internal_brake_active() const;
+  void _internal_set_brake_active(::PROTOBUF_NAMESPACE_ID::uint32 value);
+  public:
+
+  // optional uint32 brake_type = 49;
+  bool has_brake_type() const;
+  private:
+  bool _internal_has_brake_type() const;
+  public:
+  void clear_brake_type();
+  ::PROTOBUF_NAMESPACE_ID::uint32 brake_type() const;
+  void set_brake_type(::PROTOBUF_NAMESPACE_ID::uint32 value);
+  private:
+  ::PROTOBUF_NAMESPACE_ID::uint32 _internal_brake_type() const;
+  void _internal_set_brake_type(::PROTOBUF_NAMESPACE_ID::uint32 value);
+  public:
+
+  // optional float niuju_y = 50;
+  bool has_niuju_y() const;
+  private:
+  bool _internal_has_niuju_y() const;
+  public:
+  void clear_niuju_y();
+  float niuju_y() const;
+  void set_niuju_y(float value);
+  private:
+  float _internal_niuju_y() const;
+  void _internal_set_niuju_y(float value);
+  public:
+
+  // optional uint32 auto_mode = 51;
+  bool has_auto_mode() const;
+  private:
+  bool _internal_has_auto_mode() const;
+  public:
+  void clear_auto_mode();
+  ::PROTOBUF_NAMESPACE_ID::uint32 auto_mode() const;
+  void set_auto_mode(::PROTOBUF_NAMESPACE_ID::uint32 value);
+  private:
+  ::PROTOBUF_NAMESPACE_ID::uint32 _internal_auto_mode() const;
+  void _internal_set_auto_mode(::PROTOBUF_NAMESPACE_ID::uint32 value);
+  public:
+
+  // @@protoc_insertion_point(class_scope:iv.brain.decition)
+ private:
+  class _Internal;
+
+  template <typename T> friend class ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper;
+  typedef void InternalArenaConstructable_;
+  typedef void DestructorSkippable_;
+  ::PROTOBUF_NAMESPACE_ID::internal::HasBits<2> _has_bits_;
+  mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_;
+  float speed_;
+  float wheelangle_;
+  float wheelspeed_;
+  float lateraltorque_;
+  float brake_;
+  float accelerator_;
+  float torque_;
+  bool leftlamp_;
+  bool rightlamp_;
+  bool doublespark_;
+  bool headlight_;
+  ::PROTOBUF_NAMESPACE_ID::int32 dippedlight_;
+  bool highbeam_;
+  bool taillight_;
+  bool domelight_;
+  bool foglamp_;
+  ::PROTOBUF_NAMESPACE_ID::int32 engine_;
+  ::PROTOBUF_NAMESPACE_ID::int32 mode_;
+  ::PROTOBUF_NAMESPACE_ID::int32 handbrake_;
+  bool backuplight_;
+  bool brakelamp_;
+  bool speak_;
+  bool air_enable_;
+  ::PROTOBUF_NAMESPACE_ID::int32 door_;
+  ::PROTOBUF_NAMESPACE_ID::int32 gear_;
+  ::PROTOBUF_NAMESPACE_ID::int32 wiper_;
+  ::PROTOBUF_NAMESPACE_ID::int32 grade_;
+  float ttc_;
+  float air_temp_;
+  float air_mode_;
+  float wind_level_;
+  ::PROTOBUF_NAMESPACE_ID::int32 roof_light_;
+  ::PROTOBUF_NAMESPACE_ID::int32 home_light_;
+  float air_worktime_;
+  float air_offtime_;
+  bool air_on_;
+  bool air_ac_;
+  bool air_circle_;
+  bool air_auto_;
+  bool air_off_;
+  ::PROTOBUF_NAMESPACE_ID::uint32 window_fl_;
+  ::PROTOBUF_NAMESPACE_ID::uint32 window_fr_;
+  ::PROTOBUF_NAMESPACE_ID::uint32 window_rl_;
+  ::PROTOBUF_NAMESPACE_ID::uint32 window_rr_;
+  ::PROTOBUF_NAMESPACE_ID::uint32 angle_mode_;
+  ::PROTOBUF_NAMESPACE_ID::uint32 angle_active_;
+  ::PROTOBUF_NAMESPACE_ID::uint32 acc_active_;
+  ::PROTOBUF_NAMESPACE_ID::uint32 brake_active_;
+  ::PROTOBUF_NAMESPACE_ID::uint32 brake_type_;
+  float niuju_y_;
+  ::PROTOBUF_NAMESPACE_ID::uint32 auto_mode_;
+  friend struct ::TableStruct_decition_2eproto;
+};
+// ===================================================================
+
+
+// ===================================================================
+
+#ifdef __GNUC__
+  #pragma GCC diagnostic push
+  #pragma GCC diagnostic ignored "-Wstrict-aliasing"
+#endif  // __GNUC__
+// decition
+
+// optional float speed = 1;
+inline bool decition::_internal_has_speed() const {
+  bool value = (_has_bits_[0] & 0x00000001u) != 0;
+  return value;
+}
+inline bool decition::has_speed() const {
+  return _internal_has_speed();
+}
+inline void decition::clear_speed() {
+  speed_ = 0;
+  _has_bits_[0] &= ~0x00000001u;
+}
+inline float decition::_internal_speed() const {
+  return speed_;
+}
+inline float decition::speed() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.speed)
+  return _internal_speed();
+}
+inline void decition::_internal_set_speed(float value) {
+  _has_bits_[0] |= 0x00000001u;
+  speed_ = value;
+}
+inline void decition::set_speed(float value) {
+  _internal_set_speed(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.speed)
+}
+
+// optional float wheelAngle = 2;
+inline bool decition::_internal_has_wheelangle() const {
+  bool value = (_has_bits_[0] & 0x00000002u) != 0;
+  return value;
+}
+inline bool decition::has_wheelangle() const {
+  return _internal_has_wheelangle();
+}
+inline void decition::clear_wheelangle() {
+  wheelangle_ = 0;
+  _has_bits_[0] &= ~0x00000002u;
+}
+inline float decition::_internal_wheelangle() const {
+  return wheelangle_;
+}
+inline float decition::wheelangle() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.wheelAngle)
+  return _internal_wheelangle();
+}
+inline void decition::_internal_set_wheelangle(float value) {
+  _has_bits_[0] |= 0x00000002u;
+  wheelangle_ = value;
+}
+inline void decition::set_wheelangle(float value) {
+  _internal_set_wheelangle(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.wheelAngle)
+}
+
+// optional float wheelSpeed = 3;
+inline bool decition::_internal_has_wheelspeed() const {
+  bool value = (_has_bits_[0] & 0x00000004u) != 0;
+  return value;
+}
+inline bool decition::has_wheelspeed() const {
+  return _internal_has_wheelspeed();
+}
+inline void decition::clear_wheelspeed() {
+  wheelspeed_ = 0;
+  _has_bits_[0] &= ~0x00000004u;
+}
+inline float decition::_internal_wheelspeed() const {
+  return wheelspeed_;
+}
+inline float decition::wheelspeed() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.wheelSpeed)
+  return _internal_wheelspeed();
+}
+inline void decition::_internal_set_wheelspeed(float value) {
+  _has_bits_[0] |= 0x00000004u;
+  wheelspeed_ = value;
+}
+inline void decition::set_wheelspeed(float value) {
+  _internal_set_wheelspeed(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.wheelSpeed)
+}
+
+// optional float lateralTorque = 4;
+inline bool decition::_internal_has_lateraltorque() const {
+  bool value = (_has_bits_[0] & 0x00000008u) != 0;
+  return value;
+}
+inline bool decition::has_lateraltorque() const {
+  return _internal_has_lateraltorque();
+}
+inline void decition::clear_lateraltorque() {
+  lateraltorque_ = 0;
+  _has_bits_[0] &= ~0x00000008u;
+}
+inline float decition::_internal_lateraltorque() const {
+  return lateraltorque_;
+}
+inline float decition::lateraltorque() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.lateralTorque)
+  return _internal_lateraltorque();
+}
+inline void decition::_internal_set_lateraltorque(float value) {
+  _has_bits_[0] |= 0x00000008u;
+  lateraltorque_ = value;
+}
+inline void decition::set_lateraltorque(float value) {
+  _internal_set_lateraltorque(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.lateralTorque)
+}
+
+// optional float brake = 5;
+inline bool decition::_internal_has_brake() const {
+  bool value = (_has_bits_[0] & 0x00000010u) != 0;
+  return value;
+}
+inline bool decition::has_brake() const {
+  return _internal_has_brake();
+}
+inline void decition::clear_brake() {
+  brake_ = 0;
+  _has_bits_[0] &= ~0x00000010u;
+}
+inline float decition::_internal_brake() const {
+  return brake_;
+}
+inline float decition::brake() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.brake)
+  return _internal_brake();
+}
+inline void decition::_internal_set_brake(float value) {
+  _has_bits_[0] |= 0x00000010u;
+  brake_ = value;
+}
+inline void decition::set_brake(float value) {
+  _internal_set_brake(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.brake)
+}
+
+// optional float accelerator = 6;
+inline bool decition::_internal_has_accelerator() const {
+  bool value = (_has_bits_[0] & 0x00000020u) != 0;
+  return value;
+}
+inline bool decition::has_accelerator() const {
+  return _internal_has_accelerator();
+}
+inline void decition::clear_accelerator() {
+  accelerator_ = 0;
+  _has_bits_[0] &= ~0x00000020u;
+}
+inline float decition::_internal_accelerator() const {
+  return accelerator_;
+}
+inline float decition::accelerator() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.accelerator)
+  return _internal_accelerator();
+}
+inline void decition::_internal_set_accelerator(float value) {
+  _has_bits_[0] |= 0x00000020u;
+  accelerator_ = value;
+}
+inline void decition::set_accelerator(float value) {
+  _internal_set_accelerator(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.accelerator)
+}
+
+// optional float torque = 7;
+inline bool decition::_internal_has_torque() const {
+  bool value = (_has_bits_[0] & 0x00000040u) != 0;
+  return value;
+}
+inline bool decition::has_torque() const {
+  return _internal_has_torque();
+}
+inline void decition::clear_torque() {
+  torque_ = 0;
+  _has_bits_[0] &= ~0x00000040u;
+}
+inline float decition::_internal_torque() const {
+  return torque_;
+}
+inline float decition::torque() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.torque)
+  return _internal_torque();
+}
+inline void decition::_internal_set_torque(float value) {
+  _has_bits_[0] |= 0x00000040u;
+  torque_ = value;
+}
+inline void decition::set_torque(float value) {
+  _internal_set_torque(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.torque)
+}
+
+// optional bool leftLamp = 8;
+inline bool decition::_internal_has_leftlamp() const {
+  bool value = (_has_bits_[0] & 0x00000080u) != 0;
+  return value;
+}
+inline bool decition::has_leftlamp() const {
+  return _internal_has_leftlamp();
+}
+inline void decition::clear_leftlamp() {
+  leftlamp_ = false;
+  _has_bits_[0] &= ~0x00000080u;
+}
+inline bool decition::_internal_leftlamp() const {
+  return leftlamp_;
+}
+inline bool decition::leftlamp() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.leftLamp)
+  return _internal_leftlamp();
+}
+inline void decition::_internal_set_leftlamp(bool value) {
+  _has_bits_[0] |= 0x00000080u;
+  leftlamp_ = value;
+}
+inline void decition::set_leftlamp(bool value) {
+  _internal_set_leftlamp(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.leftLamp)
+}
+
+// optional bool rightLamp = 9;
+inline bool decition::_internal_has_rightlamp() const {
+  bool value = (_has_bits_[0] & 0x00000100u) != 0;
+  return value;
+}
+inline bool decition::has_rightlamp() const {
+  return _internal_has_rightlamp();
+}
+inline void decition::clear_rightlamp() {
+  rightlamp_ = false;
+  _has_bits_[0] &= ~0x00000100u;
+}
+inline bool decition::_internal_rightlamp() const {
+  return rightlamp_;
+}
+inline bool decition::rightlamp() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.rightLamp)
+  return _internal_rightlamp();
+}
+inline void decition::_internal_set_rightlamp(bool value) {
+  _has_bits_[0] |= 0x00000100u;
+  rightlamp_ = value;
+}
+inline void decition::set_rightlamp(bool value) {
+  _internal_set_rightlamp(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.rightLamp)
+}
+
+// optional bool doubleSpark = 10;
+inline bool decition::_internal_has_doublespark() const {
+  bool value = (_has_bits_[0] & 0x00000200u) != 0;
+  return value;
+}
+inline bool decition::has_doublespark() const {
+  return _internal_has_doublespark();
+}
+inline void decition::clear_doublespark() {
+  doublespark_ = false;
+  _has_bits_[0] &= ~0x00000200u;
+}
+inline bool decition::_internal_doublespark() const {
+  return doublespark_;
+}
+inline bool decition::doublespark() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.doubleSpark)
+  return _internal_doublespark();
+}
+inline void decition::_internal_set_doublespark(bool value) {
+  _has_bits_[0] |= 0x00000200u;
+  doublespark_ = value;
+}
+inline void decition::set_doublespark(bool value) {
+  _internal_set_doublespark(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.doubleSpark)
+}
+
+// optional bool headLight = 11;
+inline bool decition::_internal_has_headlight() const {
+  bool value = (_has_bits_[0] & 0x00000400u) != 0;
+  return value;
+}
+inline bool decition::has_headlight() const {
+  return _internal_has_headlight();
+}
+inline void decition::clear_headlight() {
+  headlight_ = false;
+  _has_bits_[0] &= ~0x00000400u;
+}
+inline bool decition::_internal_headlight() const {
+  return headlight_;
+}
+inline bool decition::headlight() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.headLight)
+  return _internal_headlight();
+}
+inline void decition::_internal_set_headlight(bool value) {
+  _has_bits_[0] |= 0x00000400u;
+  headlight_ = value;
+}
+inline void decition::set_headlight(bool value) {
+  _internal_set_headlight(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.headLight)
+}
+
+// optional bool highBeam = 12;
+inline bool decition::_internal_has_highbeam() const {
+  bool value = (_has_bits_[0] & 0x00001000u) != 0;
+  return value;
+}
+inline bool decition::has_highbeam() const {
+  return _internal_has_highbeam();
+}
+inline void decition::clear_highbeam() {
+  highbeam_ = false;
+  _has_bits_[0] &= ~0x00001000u;
+}
+inline bool decition::_internal_highbeam() const {
+  return highbeam_;
+}
+inline bool decition::highbeam() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.highBeam)
+  return _internal_highbeam();
+}
+inline void decition::_internal_set_highbeam(bool value) {
+  _has_bits_[0] |= 0x00001000u;
+  highbeam_ = value;
+}
+inline void decition::set_highbeam(bool value) {
+  _internal_set_highbeam(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.highBeam)
+}
+
+// optional int32 dippedLight = 13;
+inline bool decition::_internal_has_dippedlight() const {
+  bool value = (_has_bits_[0] & 0x00000800u) != 0;
+  return value;
+}
+inline bool decition::has_dippedlight() const {
+  return _internal_has_dippedlight();
+}
+inline void decition::clear_dippedlight() {
+  dippedlight_ = 0;
+  _has_bits_[0] &= ~0x00000800u;
+}
+inline ::PROTOBUF_NAMESPACE_ID::int32 decition::_internal_dippedlight() const {
+  return dippedlight_;
+}
+inline ::PROTOBUF_NAMESPACE_ID::int32 decition::dippedlight() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.dippedLight)
+  return _internal_dippedlight();
+}
+inline void decition::_internal_set_dippedlight(::PROTOBUF_NAMESPACE_ID::int32 value) {
+  _has_bits_[0] |= 0x00000800u;
+  dippedlight_ = value;
+}
+inline void decition::set_dippedlight(::PROTOBUF_NAMESPACE_ID::int32 value) {
+  _internal_set_dippedlight(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.dippedLight)
+}
+
+// optional bool tailLight = 14;
+inline bool decition::_internal_has_taillight() const {
+  bool value = (_has_bits_[0] & 0x00002000u) != 0;
+  return value;
+}
+inline bool decition::has_taillight() const {
+  return _internal_has_taillight();
+}
+inline void decition::clear_taillight() {
+  taillight_ = false;
+  _has_bits_[0] &= ~0x00002000u;
+}
+inline bool decition::_internal_taillight() const {
+  return taillight_;
+}
+inline bool decition::taillight() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.tailLight)
+  return _internal_taillight();
+}
+inline void decition::_internal_set_taillight(bool value) {
+  _has_bits_[0] |= 0x00002000u;
+  taillight_ = value;
+}
+inline void decition::set_taillight(bool value) {
+  _internal_set_taillight(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.tailLight)
+}
+
+// optional bool domeLight = 15;
+inline bool decition::_internal_has_domelight() const {
+  bool value = (_has_bits_[0] & 0x00004000u) != 0;
+  return value;
+}
+inline bool decition::has_domelight() const {
+  return _internal_has_domelight();
+}
+inline void decition::clear_domelight() {
+  domelight_ = false;
+  _has_bits_[0] &= ~0x00004000u;
+}
+inline bool decition::_internal_domelight() const {
+  return domelight_;
+}
+inline bool decition::domelight() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.domeLight)
+  return _internal_domelight();
+}
+inline void decition::_internal_set_domelight(bool value) {
+  _has_bits_[0] |= 0x00004000u;
+  domelight_ = value;
+}
+inline void decition::set_domelight(bool value) {
+  _internal_set_domelight(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.domeLight)
+}
+
+// optional bool fogLamp = 16;
+inline bool decition::_internal_has_foglamp() const {
+  bool value = (_has_bits_[0] & 0x00008000u) != 0;
+  return value;
+}
+inline bool decition::has_foglamp() const {
+  return _internal_has_foglamp();
+}
+inline void decition::clear_foglamp() {
+  foglamp_ = false;
+  _has_bits_[0] &= ~0x00008000u;
+}
+inline bool decition::_internal_foglamp() const {
+  return foglamp_;
+}
+inline bool decition::foglamp() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.fogLamp)
+  return _internal_foglamp();
+}
+inline void decition::_internal_set_foglamp(bool value) {
+  _has_bits_[0] |= 0x00008000u;
+  foglamp_ = value;
+}
+inline void decition::set_foglamp(bool value) {
+  _internal_set_foglamp(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.fogLamp)
+}
+
+// optional bool backupLight = 17;
+inline bool decition::_internal_has_backuplight() const {
+  bool value = (_has_bits_[0] & 0x00080000u) != 0;
+  return value;
+}
+inline bool decition::has_backuplight() const {
+  return _internal_has_backuplight();
+}
+inline void decition::clear_backuplight() {
+  backuplight_ = false;
+  _has_bits_[0] &= ~0x00080000u;
+}
+inline bool decition::_internal_backuplight() const {
+  return backuplight_;
+}
+inline bool decition::backuplight() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.backupLight)
+  return _internal_backuplight();
+}
+inline void decition::_internal_set_backuplight(bool value) {
+  _has_bits_[0] |= 0x00080000u;
+  backuplight_ = value;
+}
+inline void decition::set_backuplight(bool value) {
+  _internal_set_backuplight(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.backupLight)
+}
+
+// optional bool brakeLamp = 18;
+inline bool decition::_internal_has_brakelamp() const {
+  bool value = (_has_bits_[0] & 0x00100000u) != 0;
+  return value;
+}
+inline bool decition::has_brakelamp() const {
+  return _internal_has_brakelamp();
+}
+inline void decition::clear_brakelamp() {
+  brakelamp_ = false;
+  _has_bits_[0] &= ~0x00100000u;
+}
+inline bool decition::_internal_brakelamp() const {
+  return brakelamp_;
+}
+inline bool decition::brakelamp() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.brakeLamp)
+  return _internal_brakelamp();
+}
+inline void decition::_internal_set_brakelamp(bool value) {
+  _has_bits_[0] |= 0x00100000u;
+  brakelamp_ = value;
+}
+inline void decition::set_brakelamp(bool value) {
+  _internal_set_brakelamp(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.brakeLamp)
+}
+
+// optional int32 engine = 19;
+inline bool decition::_internal_has_engine() const {
+  bool value = (_has_bits_[0] & 0x00010000u) != 0;
+  return value;
+}
+inline bool decition::has_engine() const {
+  return _internal_has_engine();
+}
+inline void decition::clear_engine() {
+  engine_ = 0;
+  _has_bits_[0] &= ~0x00010000u;
+}
+inline ::PROTOBUF_NAMESPACE_ID::int32 decition::_internal_engine() const {
+  return engine_;
+}
+inline ::PROTOBUF_NAMESPACE_ID::int32 decition::engine() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.engine)
+  return _internal_engine();
+}
+inline void decition::_internal_set_engine(::PROTOBUF_NAMESPACE_ID::int32 value) {
+  _has_bits_[0] |= 0x00010000u;
+  engine_ = value;
+}
+inline void decition::set_engine(::PROTOBUF_NAMESPACE_ID::int32 value) {
+  _internal_set_engine(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.engine)
+}
+
+// optional int32 mode = 20;
+inline bool decition::_internal_has_mode() const {
+  bool value = (_has_bits_[0] & 0x00020000u) != 0;
+  return value;
+}
+inline bool decition::has_mode() const {
+  return _internal_has_mode();
+}
+inline void decition::clear_mode() {
+  mode_ = 0;
+  _has_bits_[0] &= ~0x00020000u;
+}
+inline ::PROTOBUF_NAMESPACE_ID::int32 decition::_internal_mode() const {
+  return mode_;
+}
+inline ::PROTOBUF_NAMESPACE_ID::int32 decition::mode() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.mode)
+  return _internal_mode();
+}
+inline void decition::_internal_set_mode(::PROTOBUF_NAMESPACE_ID::int32 value) {
+  _has_bits_[0] |= 0x00020000u;
+  mode_ = value;
+}
+inline void decition::set_mode(::PROTOBUF_NAMESPACE_ID::int32 value) {
+  _internal_set_mode(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.mode)
+}
+
+// optional int32 handBrake = 21;
+inline bool decition::_internal_has_handbrake() const {
+  bool value = (_has_bits_[0] & 0x00040000u) != 0;
+  return value;
+}
+inline bool decition::has_handbrake() const {
+  return _internal_has_handbrake();
+}
+inline void decition::clear_handbrake() {
+  handbrake_ = 0;
+  _has_bits_[0] &= ~0x00040000u;
+}
+inline ::PROTOBUF_NAMESPACE_ID::int32 decition::_internal_handbrake() const {
+  return handbrake_;
+}
+inline ::PROTOBUF_NAMESPACE_ID::int32 decition::handbrake() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.handBrake)
+  return _internal_handbrake();
+}
+inline void decition::_internal_set_handbrake(::PROTOBUF_NAMESPACE_ID::int32 value) {
+  _has_bits_[0] |= 0x00040000u;
+  handbrake_ = value;
+}
+inline void decition::set_handbrake(::PROTOBUF_NAMESPACE_ID::int32 value) {
+  _internal_set_handbrake(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.handBrake)
+}
+
+// optional bool speak = 22;
+inline bool decition::_internal_has_speak() const {
+  bool value = (_has_bits_[0] & 0x00200000u) != 0;
+  return value;
+}
+inline bool decition::has_speak() const {
+  return _internal_has_speak();
+}
+inline void decition::clear_speak() {
+  speak_ = false;
+  _has_bits_[0] &= ~0x00200000u;
+}
+inline bool decition::_internal_speak() const {
+  return speak_;
+}
+inline bool decition::speak() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.speak)
+  return _internal_speak();
+}
+inline void decition::_internal_set_speak(bool value) {
+  _has_bits_[0] |= 0x00200000u;
+  speak_ = value;
+}
+inline void decition::set_speak(bool value) {
+  _internal_set_speak(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.speak)
+}
+
+// optional int32 door = 23;
+inline bool decition::_internal_has_door() const {
+  bool value = (_has_bits_[0] & 0x00800000u) != 0;
+  return value;
+}
+inline bool decition::has_door() const {
+  return _internal_has_door();
+}
+inline void decition::clear_door() {
+  door_ = 0;
+  _has_bits_[0] &= ~0x00800000u;
+}
+inline ::PROTOBUF_NAMESPACE_ID::int32 decition::_internal_door() const {
+  return door_;
+}
+inline ::PROTOBUF_NAMESPACE_ID::int32 decition::door() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.door)
+  return _internal_door();
+}
+inline void decition::_internal_set_door(::PROTOBUF_NAMESPACE_ID::int32 value) {
+  _has_bits_[0] |= 0x00800000u;
+  door_ = value;
+}
+inline void decition::set_door(::PROTOBUF_NAMESPACE_ID::int32 value) {
+  _internal_set_door(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.door)
+}
+
+// optional int32 gear = 24;
+inline bool decition::_internal_has_gear() const {
+  bool value = (_has_bits_[0] & 0x01000000u) != 0;
+  return value;
+}
+inline bool decition::has_gear() const {
+  return _internal_has_gear();
+}
+inline void decition::clear_gear() {
+  gear_ = 0;
+  _has_bits_[0] &= ~0x01000000u;
+}
+inline ::PROTOBUF_NAMESPACE_ID::int32 decition::_internal_gear() const {
+  return gear_;
+}
+inline ::PROTOBUF_NAMESPACE_ID::int32 decition::gear() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.gear)
+  return _internal_gear();
+}
+inline void decition::_internal_set_gear(::PROTOBUF_NAMESPACE_ID::int32 value) {
+  _has_bits_[0] |= 0x01000000u;
+  gear_ = value;
+}
+inline void decition::set_gear(::PROTOBUF_NAMESPACE_ID::int32 value) {
+  _internal_set_gear(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.gear)
+}
+
+// optional int32 wiper = 25;
+inline bool decition::_internal_has_wiper() const {
+  bool value = (_has_bits_[0] & 0x02000000u) != 0;
+  return value;
+}
+inline bool decition::has_wiper() const {
+  return _internal_has_wiper();
+}
+inline void decition::clear_wiper() {
+  wiper_ = 0;
+  _has_bits_[0] &= ~0x02000000u;
+}
+inline ::PROTOBUF_NAMESPACE_ID::int32 decition::_internal_wiper() const {
+  return wiper_;
+}
+inline ::PROTOBUF_NAMESPACE_ID::int32 decition::wiper() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.wiper)
+  return _internal_wiper();
+}
+inline void decition::_internal_set_wiper(::PROTOBUF_NAMESPACE_ID::int32 value) {
+  _has_bits_[0] |= 0x02000000u;
+  wiper_ = value;
+}
+inline void decition::set_wiper(::PROTOBUF_NAMESPACE_ID::int32 value) {
+  _internal_set_wiper(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.wiper)
+}
+
+// optional int32 grade = 26;
+inline bool decition::_internal_has_grade() const {
+  bool value = (_has_bits_[0] & 0x04000000u) != 0;
+  return value;
+}
+inline bool decition::has_grade() const {
+  return _internal_has_grade();
+}
+inline void decition::clear_grade() {
+  grade_ = 0;
+  _has_bits_[0] &= ~0x04000000u;
+}
+inline ::PROTOBUF_NAMESPACE_ID::int32 decition::_internal_grade() const {
+  return grade_;
+}
+inline ::PROTOBUF_NAMESPACE_ID::int32 decition::grade() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.grade)
+  return _internal_grade();
+}
+inline void decition::_internal_set_grade(::PROTOBUF_NAMESPACE_ID::int32 value) {
+  _has_bits_[0] |= 0x04000000u;
+  grade_ = value;
+}
+inline void decition::set_grade(::PROTOBUF_NAMESPACE_ID::int32 value) {
+  _internal_set_grade(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.grade)
+}
+
+// optional float ttc = 27;
+inline bool decition::_internal_has_ttc() const {
+  bool value = (_has_bits_[0] & 0x08000000u) != 0;
+  return value;
+}
+inline bool decition::has_ttc() const {
+  return _internal_has_ttc();
+}
+inline void decition::clear_ttc() {
+  ttc_ = 0;
+  _has_bits_[0] &= ~0x08000000u;
+}
+inline float decition::_internal_ttc() const {
+  return ttc_;
+}
+inline float decition::ttc() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.ttc)
+  return _internal_ttc();
+}
+inline void decition::_internal_set_ttc(float value) {
+  _has_bits_[0] |= 0x08000000u;
+  ttc_ = value;
+}
+inline void decition::set_ttc(float value) {
+  _internal_set_ttc(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.ttc)
+}
+
+// optional bool air_enable = 28;
+inline bool decition::_internal_has_air_enable() const {
+  bool value = (_has_bits_[0] & 0x00400000u) != 0;
+  return value;
+}
+inline bool decition::has_air_enable() const {
+  return _internal_has_air_enable();
+}
+inline void decition::clear_air_enable() {
+  air_enable_ = false;
+  _has_bits_[0] &= ~0x00400000u;
+}
+inline bool decition::_internal_air_enable() const {
+  return air_enable_;
+}
+inline bool decition::air_enable() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.air_enable)
+  return _internal_air_enable();
+}
+inline void decition::_internal_set_air_enable(bool value) {
+  _has_bits_[0] |= 0x00400000u;
+  air_enable_ = value;
+}
+inline void decition::set_air_enable(bool value) {
+  _internal_set_air_enable(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.air_enable)
+}
+
+// optional float air_temp = 29;
+inline bool decition::_internal_has_air_temp() const {
+  bool value = (_has_bits_[0] & 0x10000000u) != 0;
+  return value;
+}
+inline bool decition::has_air_temp() const {
+  return _internal_has_air_temp();
+}
+inline void decition::clear_air_temp() {
+  air_temp_ = 0;
+  _has_bits_[0] &= ~0x10000000u;
+}
+inline float decition::_internal_air_temp() const {
+  return air_temp_;
+}
+inline float decition::air_temp() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.air_temp)
+  return _internal_air_temp();
+}
+inline void decition::_internal_set_air_temp(float value) {
+  _has_bits_[0] |= 0x10000000u;
+  air_temp_ = value;
+}
+inline void decition::set_air_temp(float value) {
+  _internal_set_air_temp(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.air_temp)
+}
+
+// optional float air_mode = 30;
+inline bool decition::_internal_has_air_mode() const {
+  bool value = (_has_bits_[0] & 0x20000000u) != 0;
+  return value;
+}
+inline bool decition::has_air_mode() const {
+  return _internal_has_air_mode();
+}
+inline void decition::clear_air_mode() {
+  air_mode_ = 0;
+  _has_bits_[0] &= ~0x20000000u;
+}
+inline float decition::_internal_air_mode() const {
+  return air_mode_;
+}
+inline float decition::air_mode() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.air_mode)
+  return _internal_air_mode();
+}
+inline void decition::_internal_set_air_mode(float value) {
+  _has_bits_[0] |= 0x20000000u;
+  air_mode_ = value;
+}
+inline void decition::set_air_mode(float value) {
+  _internal_set_air_mode(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.air_mode)
+}
+
+// optional float wind_level = 31;
+inline bool decition::_internal_has_wind_level() const {
+  bool value = (_has_bits_[0] & 0x40000000u) != 0;
+  return value;
+}
+inline bool decition::has_wind_level() const {
+  return _internal_has_wind_level();
+}
+inline void decition::clear_wind_level() {
+  wind_level_ = 0;
+  _has_bits_[0] &= ~0x40000000u;
+}
+inline float decition::_internal_wind_level() const {
+  return wind_level_;
+}
+inline float decition::wind_level() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.wind_level)
+  return _internal_wind_level();
+}
+inline void decition::_internal_set_wind_level(float value) {
+  _has_bits_[0] |= 0x40000000u;
+  wind_level_ = value;
+}
+inline void decition::set_wind_level(float value) {
+  _internal_set_wind_level(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.wind_level)
+}
+
+// optional int32 roof_light = 32;
+inline bool decition::_internal_has_roof_light() const {
+  bool value = (_has_bits_[0] & 0x80000000u) != 0;
+  return value;
+}
+inline bool decition::has_roof_light() const {
+  return _internal_has_roof_light();
+}
+inline void decition::clear_roof_light() {
+  roof_light_ = 0;
+  _has_bits_[0] &= ~0x80000000u;
+}
+inline ::PROTOBUF_NAMESPACE_ID::int32 decition::_internal_roof_light() const {
+  return roof_light_;
+}
+inline ::PROTOBUF_NAMESPACE_ID::int32 decition::roof_light() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.roof_light)
+  return _internal_roof_light();
+}
+inline void decition::_internal_set_roof_light(::PROTOBUF_NAMESPACE_ID::int32 value) {
+  _has_bits_[0] |= 0x80000000u;
+  roof_light_ = value;
+}
+inline void decition::set_roof_light(::PROTOBUF_NAMESPACE_ID::int32 value) {
+  _internal_set_roof_light(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.roof_light)
+}
+
+// optional int32 home_light = 33;
+inline bool decition::_internal_has_home_light() const {
+  bool value = (_has_bits_[1] & 0x00000001u) != 0;
+  return value;
+}
+inline bool decition::has_home_light() const {
+  return _internal_has_home_light();
+}
+inline void decition::clear_home_light() {
+  home_light_ = 0;
+  _has_bits_[1] &= ~0x00000001u;
+}
+inline ::PROTOBUF_NAMESPACE_ID::int32 decition::_internal_home_light() const {
+  return home_light_;
+}
+inline ::PROTOBUF_NAMESPACE_ID::int32 decition::home_light() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.home_light)
+  return _internal_home_light();
+}
+inline void decition::_internal_set_home_light(::PROTOBUF_NAMESPACE_ID::int32 value) {
+  _has_bits_[1] |= 0x00000001u;
+  home_light_ = value;
+}
+inline void decition::set_home_light(::PROTOBUF_NAMESPACE_ID::int32 value) {
+  _internal_set_home_light(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.home_light)
+}
+
+// optional float air_worktime = 34;
+inline bool decition::_internal_has_air_worktime() const {
+  bool value = (_has_bits_[1] & 0x00000002u) != 0;
+  return value;
+}
+inline bool decition::has_air_worktime() const {
+  return _internal_has_air_worktime();
+}
+inline void decition::clear_air_worktime() {
+  air_worktime_ = 0;
+  _has_bits_[1] &= ~0x00000002u;
+}
+inline float decition::_internal_air_worktime() const {
+  return air_worktime_;
+}
+inline float decition::air_worktime() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.air_worktime)
+  return _internal_air_worktime();
+}
+inline void decition::_internal_set_air_worktime(float value) {
+  _has_bits_[1] |= 0x00000002u;
+  air_worktime_ = value;
+}
+inline void decition::set_air_worktime(float value) {
+  _internal_set_air_worktime(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.air_worktime)
+}
+
+// optional float air_offtime = 35;
+inline bool decition::_internal_has_air_offtime() const {
+  bool value = (_has_bits_[1] & 0x00000004u) != 0;
+  return value;
+}
+inline bool decition::has_air_offtime() const {
+  return _internal_has_air_offtime();
+}
+inline void decition::clear_air_offtime() {
+  air_offtime_ = 0;
+  _has_bits_[1] &= ~0x00000004u;
+}
+inline float decition::_internal_air_offtime() const {
+  return air_offtime_;
+}
+inline float decition::air_offtime() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.air_offtime)
+  return _internal_air_offtime();
+}
+inline void decition::_internal_set_air_offtime(float value) {
+  _has_bits_[1] |= 0x00000004u;
+  air_offtime_ = value;
+}
+inline void decition::set_air_offtime(float value) {
+  _internal_set_air_offtime(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.air_offtime)
+}
+
+// optional bool air_on = 36;
+inline bool decition::_internal_has_air_on() const {
+  bool value = (_has_bits_[1] & 0x00000008u) != 0;
+  return value;
+}
+inline bool decition::has_air_on() const {
+  return _internal_has_air_on();
+}
+inline void decition::clear_air_on() {
+  air_on_ = false;
+  _has_bits_[1] &= ~0x00000008u;
+}
+inline bool decition::_internal_air_on() const {
+  return air_on_;
+}
+inline bool decition::air_on() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.air_on)
+  return _internal_air_on();
+}
+inline void decition::_internal_set_air_on(bool value) {
+  _has_bits_[1] |= 0x00000008u;
+  air_on_ = value;
+}
+inline void decition::set_air_on(bool value) {
+  _internal_set_air_on(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.air_on)
+}
+
+// optional bool air_ac = 37;
+inline bool decition::_internal_has_air_ac() const {
+  bool value = (_has_bits_[1] & 0x00000010u) != 0;
+  return value;
+}
+inline bool decition::has_air_ac() const {
+  return _internal_has_air_ac();
+}
+inline void decition::clear_air_ac() {
+  air_ac_ = false;
+  _has_bits_[1] &= ~0x00000010u;
+}
+inline bool decition::_internal_air_ac() const {
+  return air_ac_;
+}
+inline bool decition::air_ac() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.air_ac)
+  return _internal_air_ac();
+}
+inline void decition::_internal_set_air_ac(bool value) {
+  _has_bits_[1] |= 0x00000010u;
+  air_ac_ = value;
+}
+inline void decition::set_air_ac(bool value) {
+  _internal_set_air_ac(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.air_ac)
+}
+
+// optional bool air_circle = 38;
+inline bool decition::_internal_has_air_circle() const {
+  bool value = (_has_bits_[1] & 0x00000020u) != 0;
+  return value;
+}
+inline bool decition::has_air_circle() const {
+  return _internal_has_air_circle();
+}
+inline void decition::clear_air_circle() {
+  air_circle_ = false;
+  _has_bits_[1] &= ~0x00000020u;
+}
+inline bool decition::_internal_air_circle() const {
+  return air_circle_;
+}
+inline bool decition::air_circle() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.air_circle)
+  return _internal_air_circle();
+}
+inline void decition::_internal_set_air_circle(bool value) {
+  _has_bits_[1] |= 0x00000020u;
+  air_circle_ = value;
+}
+inline void decition::set_air_circle(bool value) {
+  _internal_set_air_circle(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.air_circle)
+}
+
+// optional bool air_auto = 39;
+inline bool decition::_internal_has_air_auto() const {
+  bool value = (_has_bits_[1] & 0x00000040u) != 0;
+  return value;
+}
+inline bool decition::has_air_auto() const {
+  return _internal_has_air_auto();
+}
+inline void decition::clear_air_auto() {
+  air_auto_ = false;
+  _has_bits_[1] &= ~0x00000040u;
+}
+inline bool decition::_internal_air_auto() const {
+  return air_auto_;
+}
+inline bool decition::air_auto() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.air_auto)
+  return _internal_air_auto();
+}
+inline void decition::_internal_set_air_auto(bool value) {
+  _has_bits_[1] |= 0x00000040u;
+  air_auto_ = value;
+}
+inline void decition::set_air_auto(bool value) {
+  _internal_set_air_auto(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.air_auto)
+}
+
+// optional bool air_off = 40;
+inline bool decition::_internal_has_air_off() const {
+  bool value = (_has_bits_[1] & 0x00000080u) != 0;
+  return value;
+}
+inline bool decition::has_air_off() const {
+  return _internal_has_air_off();
+}
+inline void decition::clear_air_off() {
+  air_off_ = false;
+  _has_bits_[1] &= ~0x00000080u;
+}
+inline bool decition::_internal_air_off() const {
+  return air_off_;
+}
+inline bool decition::air_off() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.air_off)
+  return _internal_air_off();
+}
+inline void decition::_internal_set_air_off(bool value) {
+  _has_bits_[1] |= 0x00000080u;
+  air_off_ = value;
+}
+inline void decition::set_air_off(bool value) {
+  _internal_set_air_off(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.air_off)
+}
+
+// optional uint32 window_fl = 41;
+inline bool decition::_internal_has_window_fl() const {
+  bool value = (_has_bits_[1] & 0x00000100u) != 0;
+  return value;
+}
+inline bool decition::has_window_fl() const {
+  return _internal_has_window_fl();
+}
+inline void decition::clear_window_fl() {
+  window_fl_ = 0u;
+  _has_bits_[1] &= ~0x00000100u;
+}
+inline ::PROTOBUF_NAMESPACE_ID::uint32 decition::_internal_window_fl() const {
+  return window_fl_;
+}
+inline ::PROTOBUF_NAMESPACE_ID::uint32 decition::window_fl() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.window_fl)
+  return _internal_window_fl();
+}
+inline void decition::_internal_set_window_fl(::PROTOBUF_NAMESPACE_ID::uint32 value) {
+  _has_bits_[1] |= 0x00000100u;
+  window_fl_ = value;
+}
+inline void decition::set_window_fl(::PROTOBUF_NAMESPACE_ID::uint32 value) {
+  _internal_set_window_fl(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.window_fl)
+}
+
+// optional uint32 window_fr = 42;
+inline bool decition::_internal_has_window_fr() const {
+  bool value = (_has_bits_[1] & 0x00000200u) != 0;
+  return value;
+}
+inline bool decition::has_window_fr() const {
+  return _internal_has_window_fr();
+}
+inline void decition::clear_window_fr() {
+  window_fr_ = 0u;
+  _has_bits_[1] &= ~0x00000200u;
+}
+inline ::PROTOBUF_NAMESPACE_ID::uint32 decition::_internal_window_fr() const {
+  return window_fr_;
+}
+inline ::PROTOBUF_NAMESPACE_ID::uint32 decition::window_fr() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.window_fr)
+  return _internal_window_fr();
+}
+inline void decition::_internal_set_window_fr(::PROTOBUF_NAMESPACE_ID::uint32 value) {
+  _has_bits_[1] |= 0x00000200u;
+  window_fr_ = value;
+}
+inline void decition::set_window_fr(::PROTOBUF_NAMESPACE_ID::uint32 value) {
+  _internal_set_window_fr(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.window_fr)
+}
+
+// optional uint32 window_rl = 43;
+inline bool decition::_internal_has_window_rl() const {
+  bool value = (_has_bits_[1] & 0x00000400u) != 0;
+  return value;
+}
+inline bool decition::has_window_rl() const {
+  return _internal_has_window_rl();
+}
+inline void decition::clear_window_rl() {
+  window_rl_ = 0u;
+  _has_bits_[1] &= ~0x00000400u;
+}
+inline ::PROTOBUF_NAMESPACE_ID::uint32 decition::_internal_window_rl() const {
+  return window_rl_;
+}
+inline ::PROTOBUF_NAMESPACE_ID::uint32 decition::window_rl() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.window_rl)
+  return _internal_window_rl();
+}
+inline void decition::_internal_set_window_rl(::PROTOBUF_NAMESPACE_ID::uint32 value) {
+  _has_bits_[1] |= 0x00000400u;
+  window_rl_ = value;
+}
+inline void decition::set_window_rl(::PROTOBUF_NAMESPACE_ID::uint32 value) {
+  _internal_set_window_rl(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.window_rl)
+}
+
+// optional uint32 window_rr = 44;
+inline bool decition::_internal_has_window_rr() const {
+  bool value = (_has_bits_[1] & 0x00000800u) != 0;
+  return value;
+}
+inline bool decition::has_window_rr() const {
+  return _internal_has_window_rr();
+}
+inline void decition::clear_window_rr() {
+  window_rr_ = 0u;
+  _has_bits_[1] &= ~0x00000800u;
+}
+inline ::PROTOBUF_NAMESPACE_ID::uint32 decition::_internal_window_rr() const {
+  return window_rr_;
+}
+inline ::PROTOBUF_NAMESPACE_ID::uint32 decition::window_rr() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.window_rr)
+  return _internal_window_rr();
+}
+inline void decition::_internal_set_window_rr(::PROTOBUF_NAMESPACE_ID::uint32 value) {
+  _has_bits_[1] |= 0x00000800u;
+  window_rr_ = value;
+}
+inline void decition::set_window_rr(::PROTOBUF_NAMESPACE_ID::uint32 value) {
+  _internal_set_window_rr(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.window_rr)
+}
+
+// optional uint32 angle_mode = 45;
+inline bool decition::_internal_has_angle_mode() const {
+  bool value = (_has_bits_[1] & 0x00001000u) != 0;
+  return value;
+}
+inline bool decition::has_angle_mode() const {
+  return _internal_has_angle_mode();
+}
+inline void decition::clear_angle_mode() {
+  angle_mode_ = 0u;
+  _has_bits_[1] &= ~0x00001000u;
+}
+inline ::PROTOBUF_NAMESPACE_ID::uint32 decition::_internal_angle_mode() const {
+  return angle_mode_;
+}
+inline ::PROTOBUF_NAMESPACE_ID::uint32 decition::angle_mode() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.angle_mode)
+  return _internal_angle_mode();
+}
+inline void decition::_internal_set_angle_mode(::PROTOBUF_NAMESPACE_ID::uint32 value) {
+  _has_bits_[1] |= 0x00001000u;
+  angle_mode_ = value;
+}
+inline void decition::set_angle_mode(::PROTOBUF_NAMESPACE_ID::uint32 value) {
+  _internal_set_angle_mode(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.angle_mode)
+}
+
+// optional uint32 angle_active = 46;
+inline bool decition::_internal_has_angle_active() const {
+  bool value = (_has_bits_[1] & 0x00002000u) != 0;
+  return value;
+}
+inline bool decition::has_angle_active() const {
+  return _internal_has_angle_active();
+}
+inline void decition::clear_angle_active() {
+  angle_active_ = 0u;
+  _has_bits_[1] &= ~0x00002000u;
+}
+inline ::PROTOBUF_NAMESPACE_ID::uint32 decition::_internal_angle_active() const {
+  return angle_active_;
+}
+inline ::PROTOBUF_NAMESPACE_ID::uint32 decition::angle_active() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.angle_active)
+  return _internal_angle_active();
+}
+inline void decition::_internal_set_angle_active(::PROTOBUF_NAMESPACE_ID::uint32 value) {
+  _has_bits_[1] |= 0x00002000u;
+  angle_active_ = value;
+}
+inline void decition::set_angle_active(::PROTOBUF_NAMESPACE_ID::uint32 value) {
+  _internal_set_angle_active(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.angle_active)
+}
+
+// optional uint32 acc_active = 47;
+inline bool decition::_internal_has_acc_active() const {
+  bool value = (_has_bits_[1] & 0x00004000u) != 0;
+  return value;
+}
+inline bool decition::has_acc_active() const {
+  return _internal_has_acc_active();
+}
+inline void decition::clear_acc_active() {
+  acc_active_ = 0u;
+  _has_bits_[1] &= ~0x00004000u;
+}
+inline ::PROTOBUF_NAMESPACE_ID::uint32 decition::_internal_acc_active() const {
+  return acc_active_;
+}
+inline ::PROTOBUF_NAMESPACE_ID::uint32 decition::acc_active() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.acc_active)
+  return _internal_acc_active();
+}
+inline void decition::_internal_set_acc_active(::PROTOBUF_NAMESPACE_ID::uint32 value) {
+  _has_bits_[1] |= 0x00004000u;
+  acc_active_ = value;
+}
+inline void decition::set_acc_active(::PROTOBUF_NAMESPACE_ID::uint32 value) {
+  _internal_set_acc_active(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.acc_active)
+}
+
+// optional uint32 brake_active = 48;
+inline bool decition::_internal_has_brake_active() const {
+  bool value = (_has_bits_[1] & 0x00008000u) != 0;
+  return value;
+}
+inline bool decition::has_brake_active() const {
+  return _internal_has_brake_active();
+}
+inline void decition::clear_brake_active() {
+  brake_active_ = 0u;
+  _has_bits_[1] &= ~0x00008000u;
+}
+inline ::PROTOBUF_NAMESPACE_ID::uint32 decition::_internal_brake_active() const {
+  return brake_active_;
+}
+inline ::PROTOBUF_NAMESPACE_ID::uint32 decition::brake_active() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.brake_active)
+  return _internal_brake_active();
+}
+inline void decition::_internal_set_brake_active(::PROTOBUF_NAMESPACE_ID::uint32 value) {
+  _has_bits_[1] |= 0x00008000u;
+  brake_active_ = value;
+}
+inline void decition::set_brake_active(::PROTOBUF_NAMESPACE_ID::uint32 value) {
+  _internal_set_brake_active(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.brake_active)
+}
+
+// optional uint32 brake_type = 49;
+inline bool decition::_internal_has_brake_type() const {
+  bool value = (_has_bits_[1] & 0x00010000u) != 0;
+  return value;
+}
+inline bool decition::has_brake_type() const {
+  return _internal_has_brake_type();
+}
+inline void decition::clear_brake_type() {
+  brake_type_ = 0u;
+  _has_bits_[1] &= ~0x00010000u;
+}
+inline ::PROTOBUF_NAMESPACE_ID::uint32 decition::_internal_brake_type() const {
+  return brake_type_;
+}
+inline ::PROTOBUF_NAMESPACE_ID::uint32 decition::brake_type() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.brake_type)
+  return _internal_brake_type();
+}
+inline void decition::_internal_set_brake_type(::PROTOBUF_NAMESPACE_ID::uint32 value) {
+  _has_bits_[1] |= 0x00010000u;
+  brake_type_ = value;
+}
+inline void decition::set_brake_type(::PROTOBUF_NAMESPACE_ID::uint32 value) {
+  _internal_set_brake_type(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.brake_type)
+}
+
+// optional float niuju_y = 50;
+inline bool decition::_internal_has_niuju_y() const {
+  bool value = (_has_bits_[1] & 0x00020000u) != 0;
+  return value;
+}
+inline bool decition::has_niuju_y() const {
+  return _internal_has_niuju_y();
+}
+inline void decition::clear_niuju_y() {
+  niuju_y_ = 0;
+  _has_bits_[1] &= ~0x00020000u;
+}
+inline float decition::_internal_niuju_y() const {
+  return niuju_y_;
+}
+inline float decition::niuju_y() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.niuju_y)
+  return _internal_niuju_y();
+}
+inline void decition::_internal_set_niuju_y(float value) {
+  _has_bits_[1] |= 0x00020000u;
+  niuju_y_ = value;
+}
+inline void decition::set_niuju_y(float value) {
+  _internal_set_niuju_y(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.niuju_y)
+}
+
+// optional uint32 auto_mode = 51;
+inline bool decition::_internal_has_auto_mode() const {
+  bool value = (_has_bits_[1] & 0x00040000u) != 0;
+  return value;
+}
+inline bool decition::has_auto_mode() const {
+  return _internal_has_auto_mode();
+}
+inline void decition::clear_auto_mode() {
+  auto_mode_ = 0u;
+  _has_bits_[1] &= ~0x00040000u;
+}
+inline ::PROTOBUF_NAMESPACE_ID::uint32 decition::_internal_auto_mode() const {
+  return auto_mode_;
+}
+inline ::PROTOBUF_NAMESPACE_ID::uint32 decition::auto_mode() const {
+  // @@protoc_insertion_point(field_get:iv.brain.decition.auto_mode)
+  return _internal_auto_mode();
+}
+inline void decition::_internal_set_auto_mode(::PROTOBUF_NAMESPACE_ID::uint32 value) {
+  _has_bits_[1] |= 0x00040000u;
+  auto_mode_ = value;
+}
+inline void decition::set_auto_mode(::PROTOBUF_NAMESPACE_ID::uint32 value) {
+  _internal_set_auto_mode(value);
+  // @@protoc_insertion_point(field_set:iv.brain.decition.auto_mode)
+}
+
+#ifdef __GNUC__
+  #pragma GCC diagnostic pop
+#endif  // __GNUC__
+
+// @@protoc_insertion_point(namespace_scope)
+
+}  // namespace brain
+}  // namespace iv
+
+// @@protoc_insertion_point(global_scope)
+
+#include <google/protobuf/port_undef.inc>
+#endif  // GOOGLE_PROTOBUF_INCLUDED_GOOGLE_PROTOBUF_INCLUDED_decition_2eproto

+ 114 - 0
src/ros2/src/adc_controller_shenlan_v2/include/adc_controller_shenlan_v2/vv7.h

@@ -0,0 +1,114 @@
+#pragma once
+
+#if 1
+struct Command_Bit10
+{
+    unsigned char air_temp ;
+    unsigned char air_mode : 3;
+    unsigned char air_enable : 1;
+    unsigned char air_wind_level : 3;
+    unsigned char air_reserved : 1;
+    unsigned char ignition : 2;
+    unsigned char door : 2;
+    unsigned char Reserved :2;
+    unsigned char air_on : 2;
+    unsigned char turn_light : 2;
+    unsigned char small_light : 1;
+    unsigned char near_light : 1;
+    unsigned char horn : 1;
+    unsigned char far_light : 1;
+    unsigned char fog_light : 1;
+    unsigned char wiper : 1;
+    unsigned char brake_light : 1;
+    unsigned char defrog : 1;
+    unsigned char revers_light : 1;
+    unsigned char roof_light : 1;
+    unsigned char home_light : 1;
+    unsigned char Reserved0 :3;
+    unsigned char air_work_time;
+    unsigned char  air_off_time;
+    unsigned char  checkSum;
+};
+
+
+union Command10
+{
+    Command_Bit10 bit;
+    unsigned char byte[8];
+};
+
+
+struct Command_Bit11
+{
+    unsigned char speed_limit;
+    unsigned char  aeb_H;
+    unsigned char  aeb_L;
+    unsigned char torque;
+    unsigned char brake;
+    unsigned char gear:3;
+    unsigned char Reserved :1;
+    unsigned char park :2;
+    unsigned char Reserved0 :2;
+    unsigned char Reserved1 :2;
+    unsigned char Reserved2 :2;
+    unsigned char driveMode :1;
+    unsigned char gear_enable :1;
+    unsigned char aeb_enable :1;
+    unsigned char acc_enable :1;
+    unsigned char checkSum;
+};
+
+
+
+
+union Command11
+{
+    Command_Bit11 bit;
+    unsigned char byte[8];
+};
+
+
+struct Command_Bit12
+{
+    unsigned char ang_speed;
+    unsigned char  ang_H;
+    unsigned char  ang_L;
+    unsigned char reserved0;
+    unsigned char reserved1;
+    unsigned char reserved2;
+    unsigned char Reserved : 6;
+    unsigned char ang_enable : 1;
+    unsigned char Reserved0 : 1;
+    unsigned char checkSum;
+};
+
+
+union Command12
+{
+    Command_Bit12 bit;
+    unsigned char byte[8];
+};
+
+
+struct Command_Response_Bit
+{
+    unsigned char head;
+    unsigned char grade : 2;
+    unsigned char driveMode : 2;
+    unsigned char epb : 1;
+    unsigned char epsMode : 2;
+    unsigned char  obligate: 1;
+};
+
+union Command_Response
+{
+    Command_Response_Bit bit;
+    unsigned char byte[2];
+};
+
+#else
+
+#endif
+
+
+

+ 21 - 0
src/ros2/src/adc_controller_shenlan_v2/package.xml

@@ -0,0 +1,21 @@
+<?xml version="1.0"?>
+<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
+<package format="3">
+  <name>adc_controller_shenlan_v2</name>
+  <version>0.0.0</version>
+  <description>TODO: Package description</description>
+  <maintainer email="yuchuli@catarc.ac.cn">yuchuli</maintainer>
+  <license>Apache-2.0</license>
+
+  <buildtool_depend>ament_cmake</buildtool_depend>
+
+  <test_depend>ament_lint_auto</test_depend>
+  <test_depend>ament_lint_common</test_depend>
+  <depend>rclcpp</depend>
+  <depend>adc_autoware_msgs</depend>
+  <depend>autoware_auto_control_msgs</depend>
+
+  <export>
+    <build_type>ament_cmake</build_type>
+  </export>
+</package>

+ 594 - 0
src/ros2/src/adc_controller_shenlan_v2/src/adc_controller_shenlan_v2_core.cpp

@@ -0,0 +1,594 @@
+#include "adc_controller_shenlan_v2/adc_controller_shenlan_v2_core.hpp"
+
+#include <functional>
+
+using std::placeholders::_1;
+
+// signal: @ACC_LatAngReq    //更改CANid
+#define ECU_1C4_ACC_LatAngReq_CovFactor (0.1)
+// conversion value to CAN signal
+#define ECU_1C4_ACC_LatAngReq_toS(x) ((int16_t)((x) / 0.1 + 7200))
+
+// signal: @ACC_MotorTorqueMaxLimitRequest
+#define ECU_1C4_ACC_MotorTorqueMaxLimitRequest_CovFactor (0.02)
+// conversion value to CAN signal
+#define ECU_1C4_ACC_MotorTorqueMaxLimitRequest_toS(x) ((int16_t)((x) / 0.02 + 1024))
+
+// signal: @ACC_MotorTorqueMinLimitRequest
+#define ECU_1C4_ACC_MotorTorqueMinLimitRequest_CovFactor (0.02)
+// conversion value to CAN signal
+#define ECU_1C4_ACC_MotorTorqueMinLimitRequest_toS(x) ((int16_t)((x) / 0.02 + 1024))
+
+typedef struct
+{
+    int16_t ACC_LatAngReq;
+    //uint8_t ADS_Reqmode;  //20221102, 新车没有此信号
+    int16_t ACC_MotorTorqueMaxLimitRequest;
+    uint8_t ACC_LatAngReqActive;
+    int16_t ACC_MotorTorqueMinLimitRequest;
+    //uint8_t ACC_ADCReqType; //20221102, 新车没有此信号
+} ECU_1C4_t;
+
+// signal: @ACC_AccTrqReq
+#define ECU_24E_ACC_AccTrqReq_CovFactor (1)
+// conversion value to CAN signal
+#define ECU_24E_ACC_AccTrqReq_toS(x) ((int16_t)((x) + 16384))
+
+// signal: @ACC_ACCTargetAcceleration
+#define ECU_24E_ACC_ACCTargetAcceleration_CovFactor (0.05)
+// conversion value to CAN signal
+#define ECU_24E_ACC_ACCTargetAcceleration_toS(x) ((int16_t)((x) / 0.05 + 100))
+
+// signal: @ACC_AEBTargetDeceleration
+#define ECU_24E_ACC_AEBTargetDeceleration_CovFactor (0.0005)
+// conversion value to CAN signal
+#define ECU_24E_ACC_AEBTargetDeceleration_toS(x) ((int32_t)((x) / 0.0005 + 32000))
+
+
+static int gnState = 0; //0 not act  1 act
+typedef struct
+{
+    int16_t ACC_AccTrqReq;
+    uint8_t ACC_AccTrqReqActive;
+    int16_t ACC_ACCTargetAcceleration;
+    int32_t ACC_AEBTargetDeceleration;
+    uint8_t ACC_AEBVehilceHoldReq;
+    uint8_t ADCReqMode;
+    uint8_t ACC_AEBActive;
+    uint8_t ACC_Driveoff_Request;
+    uint8_t ACC_DecToStop;
+    uint8_t ACC_CDDActive;
+    uint8_t ACC_ACCMode;
+} ECU_24E_t;
+
+typedef struct
+{
+    uint8_t CdcDoor;
+    uint8_t res1;
+    uint8_t res2;
+    uint8_t ADS_UDLCTurnLightReq;
+} ECU_25E_t;  //zhuanxiangdeng IDgenghuan
+
+unsigned char byte_1C4[64];//byte_144[8];
+unsigned char byte_24E[64];
+unsigned char byte_25E[32];
+
+ECU_1C4_t _m1C4 = {0,0,0,0};
+ECU_24E_t _m24E = {0,0,0,0,0,0,0,0,0,0,0};
+ECU_25E_t _m25E = {0,0,0,0};
+
+
+
+adc_controller_shenlan_v2_core::adc_controller_shenlan_v2_core() : Node("adc_controller_shenlan_v2")
+{
+    gdecition_def.set_brake(0);
+    gdecition_def.set_rightlamp(false);
+    gdecition_def.set_leftlamp(false);
+    gdecition_def.set_wheelangle(0);
+
+    gdecition_def.set_angle_mode(0);
+    gdecition_def.set_angle_active(0);
+    gdecition_def.set_acc_active(0);
+//    gdecition_def.set_brake_active(1);
+    gdecition_def.set_brake_type(0);
+    gdecition_def.set_auto_mode(0);
+
+    sub_msgs_chassis = this->create_subscription<adc_autoware_msgs::msg::AdcChassis>("chassis",10,
+                        std::bind(&adc_controller_shenlan_v2_core::topic_chassis_callback,this,_1));
+
+    mpthreadsend = new std::thread(&adc_controller_shenlan_v2_core::threadsend,this);
+}
+
+adc_controller_shenlan_v2_core::~adc_controller_shenlan_v2_core()
+{
+    mbtheadrun = false;
+    mpthreadsend->join();
+}
+
+void adc_controller_shenlan_v2_core::topic_chassis_callback(const adc_autoware_msgs::msg::AdcChassis & msg)
+{
+    (void)msg;
+
+    gfVehSpd = msg.vel;
+    gbHaveVehSpd = true;
+
+
+
+    gfWheelAngle = msg.angle_feedback;
+    gbHaveWheelAngle = true;
+
+}
+
+void adc_controller_shenlan_v2_core::threadsend()
+{
+    initial();
+    iv::brain::decition xdecition;
+
+    UnAcitvate();
+ //   UnAcitvate();
+
+    int nstate = 0; //0 Un 1 Activate
+//    Activate();
+    while(mbtheadrun)
+    {
+        if(gnDecitionNum <= 0)
+        {
+            if(nstate == 1)
+            {
+                UnAcitvate();
+                nstate = 0;
+            }
+            xdecition.CopyFrom(gdecition_def);
+        }
+        else
+        {
+            if(nstate == 0)
+            {
+                Activate();
+                nstate = 1;
+            }
+            gMutex.lock();
+            xdecition.CopyFrom(gdecition);
+            gMutex.unlock();
+            gnDecitionNum--;
+        }
+
+        executeDecition(xdecition);
+        ExecSend();
+        std::this_thread::sleep_for(std::chrono::milliseconds(10));
+    }
+    UnAcitvate();
+}
+
+void adc_controller_shenlan_v2_core::topic_cmd_callback(const autoware_auto_control_msgs::msg::AckermannControlCommand & msg)
+{
+    (void)msg;
+        iv::brain::decition xdecition;
+    double facc = 0;
+    double ftorque = 0;
+    double fbrake = 0;
+    double fwheelangle = 0;
+
+    facc = msg.longitudinal.acceleration;
+
+        double fVehWeight = 1800;
+     //   double fg = 9.8;
+        double fRollForce = 50;
+        const double fRatio = 2.5;
+        double fNeed = fRollForce + fVehWeight*facc;
+
+        ftorque = fNeed/fRatio;
+        fbrake = 0;
+        if(ftorque<0)
+        {
+            fbrake = facc;
+            ftorque = 0;
+        }
+
+//    facc = xctrlcmd.linear_acceleration();
+    fwheelangle = msg.lateral.steering_tire_angle * (180.0/M_PI) * 15.0;
+    if(fwheelangle>430)fwheelangle = 430;
+    if(fwheelangle<-430)fwheelangle = -430;
+    std::cout<<" acc: "<<facc<<"  wheel: "<<fwheelangle<<std::endl;
+    xdecition.set_accelerator(facc);
+    xdecition.set_brake(fbrake);
+    xdecition.set_leftlamp(false);
+    xdecition.set_rightlamp(false);
+    xdecition.set_speed(msg.longitudinal.speed * 3.6);
+    xdecition.set_wheelangle(fwheelangle);
+    xdecition.set_wheelspeed(300);
+    xdecition.set_torque(ftorque);
+    xdecition.set_mode(1);
+    xdecition.set_gear(1);
+    xdecition.set_handbrake(0);
+    xdecition.set_grade(1);
+    xdecition.set_engine(0);
+    xdecition.set_brakelamp(false);
+    xdecition.set_ttc(15);
+//    xdecition.set_air_enable(decition->air_enable);
+//    xdecition.set_air_temp(decition->air_temp);
+//    xdecition.set_air_mode(decition->air_mode);
+//    xdecition.set_wind_level(decition->wind_level);
+    xdecition.set_roof_light(0);
+    xdecition.set_home_light(0);
+//    xdecition.set_air_worktime(decition->air_worktime);
+//    xdecition.set_air_offtime(decition->air_offtime);
+//    xdecition.set_air_on(decition->air_on);
+    xdecition.set_door(0);
+    xdecition.set_dippedlight(0);
+
+    gMutex.lock();
+    gdecition.CopyFrom(xdecition);
+    gMutex.unlock();
+
+    gnDecitionNum = gnDecitionNumMax;
+}
+
+void adc_controller_shenlan_v2_core::executeDecition(const iv::brain::decition &decition)
+{
+
+
+
+
+    static int xieya = 50;
+//     std::cout<<"acc is "<<decition.torque()<<" ang is "<<decition.wheelangle()<<std::endl;
+//     std::cout<<"angle_mode is "<<decition.angle_mode()<<" angle_active is "<<decition.angle_active()<<std::endl;
+//     std::cout<<"brake_type is "<<decition.brake_type()<<" acc_active is "<<decition.acc_active()<<std::endl;
+//     std::cout<<"brake is "<<decition.brake()<<" brake_active is "<<decition.brake_active()<<std::endl;
+//     std::cout<<"auto_mode is "<<decition.auto_mode()<<" rightlamp is "<<decition.rightlamp()<<std::endl;
+
+    double fWheelAngleReq = decition.wheelangle();
+ //   double fsendinter = 0.02;
+//    if(fabs(fWheelAngleReq - gfWheelAngle)/fsendinter > gfWheelSpeedLim)
+//    {
+//        if(fWheelAngleReq > gfWheelAngle)
+//        {
+//            fWheelAngleReq = gfWheelAngle + fsendinter * gfWheelSpeedLim;
+//        }
+//        else
+//        {
+//            fWheelAngleReq = gfWheelAngle - fsendinter * gfWheelSpeedLim;
+//        }
+
+//    }
+
+//    std::cout<<" wheel req: "<<decition.wheelangle()<<" real send : "<<fWheelAngleReq<<" real whhel:"<<gfWheelAngle<< std::endl;
+
+    _m1C4.ACC_LatAngReq = ECU_1C4_ACC_LatAngReq_toS(fWheelAngleReq);
+    //_m1C4.ADS_Reqmode = decition.angle_mode(); //20221102,新车没有此信号
+    _m1C4.ACC_MotorTorqueMaxLimitRequest = ECU_1C4_ACC_MotorTorqueMaxLimitRequest_toS(10);
+    _m1C4.ACC_LatAngReqActive = decition.angle_active();
+    _m1C4.ACC_MotorTorqueMinLimitRequest = ECU_1C4_ACC_MotorTorqueMinLimitRequest_toS(-10);
+//    _m144.ACC_ADCReqType = decition.brake_type();//ADC请求类型(制动时为1,其余情况为0)
+    if(decition.brake()>(-0.0000001))
+    {
+        //_m144.ACC_ADCReqType = 0;//ADC请求类型(制动时为1,其余情况为0)//20221102,新车没有此信号
+       // _m24B.ADCReqMode = 0;//20221102,新车没有此信号
+        _m24E.ACC_DecToStop =0;
+    }
+    else
+    {
+        //_m144.ACC_ADCReqType = 1;//20221102,新车没有此信号
+       // _m24B.ADCReqMode = 1;//20221102,新车没有此信号
+         _m24E.ACC_DecToStop =1;
+    }
+
+//    std::cout<<" type: "<<(int)_m144.ACC_ADCReqType<<std::endl;
+
+
+    /*制动过程用的减速度,加速用扭矩*/
+    _m24E.ACC_AccTrqReq = ECU_24E_ACC_AccTrqReq_toS(decition.torque());
+    _m24E.ACC_AccTrqReqActive = decition.acc_active();
+    if(decition.brake()<(-5.0))
+    {
+        _m24E.ACC_ACCTargetAcceleration = ECU_24E_ACC_ACCTargetAcceleration_toS(-5.0);
+    }
+    else
+        _m24E.ACC_ACCTargetAcceleration = ECU_24E_ACC_ACCTargetAcceleration_toS(decition.brake());
+
+
+ //   std::cout<<" brake : "<<decition.brake()<<std::endl;
+ //   std::cout<<"brake acctive. "<<decition.brake_active()<<std::endl;
+    if(decition.brake()>(-0.0000001))
+    {
+
+        if(xieya > 0)
+        {
+            _m24E.ACC_CDDActive = 1;
+            _m24E.ACC_ACCTargetAcceleration = ECU_24E_ACC_ACCTargetAcceleration_toS(0.5);
+            _m24E.ACC_AccTrqReq = ECU_24E_ACC_AccTrqReq_toS(0);
+            _m24E.ACC_Driveoff_Request = 1;
+
+            //_m144.ACC_ADCReqType = 1;//20221102,新车没有此信号
+            //_m24B.ADCReqMode = 1;   //20221102,新车没有此信号
+             _m24E.ACC_DecToStop =1;
+            xieya--;
+            std::cout<<" xieya. now veh speed: "<<gfVehSpd<<std::endl;
+        }
+        else
+        {
+            _m24E.ACC_CDDActive = 0;
+            _m24E.ACC_ACCTargetAcceleration = ECU_24E_ACC_ACCTargetAcceleration_toS(0);
+            _m24E.ACC_Driveoff_Request = 0;
+        }
+    }
+    else
+    {
+        _m24E.ACC_CDDActive = 1;
+
+        _m24E.ACC_Driveoff_Request = 0;
+
+
+    }
+
+
+ //       _m24B.ACC_CDDActive = decition.brake_active();
+
+
+
+//    std::cout<<" req mode: "<<_m144.ADS_Reqmode<<std::endl;
+    //byte_144[0] = ((_m144.ACC_LatAngReq >> 9) & (0x1FU)) | ((_m144.ADS_Reqmode & (0x07U)) << 5);
+ //   qDebug(" req mode: %d byte: %02X  ",_m144.ADS_Reqmode, byte_144[0]);
+   // byte_144[1] = ((_m144.ACC_LatAngReq >> 1) & (0xFFU));
+    //byte_144[2] = ((_m144.ACC_LatAngReq & (0x01U)) << 7) | ((_m144.ACC_MotorTorqueMaxLimitRequest >> 5) & (0x3FU)) | ((_m144.ACC_LatAngReqActive & (0x01U)) << 6);
+    //byte_144[3] = ((_m144.ACC_MotorTorqueMaxLimitRequest & (0x1FU)) << 3) | ((_m144.ACC_MotorTorqueMinLimitRequest >> 8) & (0x07U));
+    //byte_144[4] = (_m144.ACC_MotorTorqueMinLimitRequest & (0xFFU));
+    //byte_144[5] = ((_m144.ACC_ADCReqType & (0x03U)) << 6);
+
+
+    byte_1C4[0] = ((_m1C4.ACC_MotorTorqueMaxLimitRequest >> 3) & (0xFFU));
+ //   qDebug(" req mode: %d byte: %02X  ",_m144.ADS_Reqmode, byte_144[0]);
+    byte_1C4[1] = ((_m1C4.ACC_MotorTorqueMaxLimitRequest & (0x07U)) << 5) | ((_m1C4.ACC_MotorTorqueMinLimitRequest >> 6) & (0x1FU));
+    byte_1C4[2] = ((_m1C4.ACC_MotorTorqueMinLimitRequest & (0x3FU)) << 2) | ((_m1C4.ACC_LatAngReq >> 12) & (0x03U));
+    byte_1C4[3] = (((_m1C4.ACC_LatAngReq>>4 )& (0xFFU)));
+   // byte_1C4[4] = (((_m1C4.ACC_LatAngReq<<4) & (0xF0U)))|((_m1C4.ACC_LatAngReqActive&(0x01U))<<3);
+    byte_1C4[4] = (((_m1C4.ACC_LatAngReq)& (0x0fU))<<4)|((_m1C4.ACC_LatAngReqActive&(0x01U))<<3);
+    //byte_1C4[5] = ((_m144.ACC_ADCReqType & (0x03U)) << 6);
+
+    //    _m24B.ACC_AEBTargetDeceleration = 0;
+    //    _m24B.ACC_AEBVehilceHoldReq = 0;
+    //    _m24B.ADCReqMode = 0;
+    //    _m24B.ACC_AEBActive = 0;
+    //    _m24B.ACC_Driveoff_Request = 0;
+    //    _m24B.ACC_DecToStop = 0;
+//    std::cout<<" brake : "<<decition.brake()<<std::endl;
+//    std::cout<<"brake acctive. "<<decition.brake_active()<<std::endl;
+    if(decition.brake()>(-0.0000001))
+    {
+        _m24E.ACC_CDDActive = 0;
+        _m24E.ACC_Driveoff_Request = 1;
+        if(xieya > 0)
+        {
+            _m24E.ACC_ACCTargetAcceleration = ECU_24E_ACC_ACCTargetAcceleration_toS(0.5);
+            xieya--;
+        }
+        else
+        {
+            _m24E.ACC_ACCTargetAcceleration = ECU_24E_ACC_ACCTargetAcceleration_toS(0);
+        }
+        _m24E.ACC_AccTrqReqActive = 1;
+        _m24E.ACC_DecToStop = 0;
+
+    }
+    else
+    {
+        _m24E.ACC_CDDActive = 1;
+
+        _m24E.ACC_Driveoff_Request = 0;
+
+        if(gbHaveVehSpd)
+        {
+            if(gfVehSpd < 0.01)
+            {
+                if(xieya != 50)std::cout<<"need xieya. "<<std::endl;
+                xieya = 50;
+
+            }
+        }
+
+        _m24E.ACC_AccTrqReqActive = 0;
+        _m24E.ACC_DecToStop = 1;
+    }
+ //       _m24B.ACC_CDDActive = decition.brake_active();
+    _m24E.ACC_ACCMode = decition.auto_mode();
+
+
+    if(gnState == 0)
+    {
+        _m24E.ACC_CDDActive = 0;
+        _m24E.ACC_Driveoff_Request = 0;
+        _m24E.ACC_ACCMode = 0;
+        _m24E.ACC_ACCTargetAcceleration = 0;
+        _m24E.ACC_AccTrqReqActive = 0;
+        _m24E.ACC_DecToStop = 0;
+
+    }
+//    std::cout<<"acc mode: "<<(int)_m24B.ACC_ACCMode<<std::endl;
+
+
+   // byte_24B[0] = ((_m24B.ACC_AccTrqReq >> 7) & (0xFFU));
+    //byte_24B[1] = ((_m24B.ACC_AccTrqReq & (0x7FU)) << 1) | (_m24B.ACC_AccTrqReqActive & (0x01U));
+    //byte_24B[2] = ((_m24B.ACC_ACCTargetAcceleration >> 3) & (0x1FU));
+    //byte_24B[3] = ((_m24B.ACC_ACCTargetAcceleration & (0x07U)) << 5) | ((_m24B.ACC_AEBTargetDeceleration >> 15) & (0x01U));
+    //byte_24B[4] = ((_m24B.ACC_AEBTargetDeceleration >> 7) & (0xFFU));
+    //byte_24B[5] = ((_m24B.ACC_AEBTargetDeceleration & (0x7FU)) << 1) | (_m24B.ACC_AEBVehilceHoldReq & (0x01U));
+    //byte_24B[6] = ((_m24B.ADCReqMode & (0x03U)) << 1) | ((_m24B.ACC_AEBActive & (0x01U)) << 3) | ((_m24B.ACC_Driveoff_Request & (0x01U)) << 5) | ((_m24B.ACC_DecToStop & (0x01U)) << 6) | ((_m24B.ACC_CDDActive & (0x01U)) << 7);
+    //byte_24B[7] = (_m24B.ACC_ACCMode & (0x07U));
+
+
+    byte_24E[0] = ((_m24E.ACC_ACCTargetAcceleration) & (0xFFU));
+    //byte_24E[1] = ((_m24B.ACC_AccTrqReq & (0x7FU)) << 1) | (_m24B.ACC_AccTrqReqActive & (0x01U));
+    //byte_24E[2] = ((_m24B.ACC_ACCTargetAcceleration >> 3) & (0x1FU));
+    byte_24E[3] = ((_m24E.ACC_DecToStop & (0x01U)) << 7);// | ((_m24B.ACC_AEBTargetDeceleration >> 15) & (0x01U));
+    //byte_24E[4] = ((_m24B.ACC_AEBTargetDeceleration >> 7) & (0xFFU));
+    byte_24E[5] = ((_m24E.ACC_CDDActive & (0x01U)) << 4);//((_m24E.ACC_AEBTargetDeceleration & (0x7FU)) << 1) | (_m24E.ACC_AEBVehilceHoldReq & (0x01U));
+    byte_24E[6] = ((_m24E.ACC_Driveoff_Request & (0x01U)) << 7)|((_m24E.ACC_ACCMode & (0x07U))<<4);//((_m24E.ADCReqMode & (0x03U)) << 1) | ((_m24E.ACC_AEBActive & (0x01U)) << 3) | ((_m24E.ACC_Driveoff_Request & (0x01U)) << 5) | ((_m24E.ACC_DecToStop & (0x01U)) << 6) | ((_m24E.ACC_CDDActive & (0x01U)) << 7);
+    byte_24E[8] = ((_m24E.ACC_AEBTargetDeceleration>>8) & (0xFFU));
+    byte_24E[9] = ((_m24E.ACC_AEBTargetDeceleration) & (0xFFU));
+    byte_24E[10] = ((_m24E.ACC_AEBActive & (0x01U)) << 7);
+    byte_24E[11] = ((_m24E.ACC_AccTrqReq>>13 )& (0x03U));
+    byte_24E[12] = ((_m24E.ACC_AccTrqReq>>5 )& (0xFFU));
+    //byte_24E[13] = ((_m24E.ACC_AccTrqReq & (0x1FU)<<3))| ((_m24E.ACC_AccTrqReqActive & (0x01U)) << 2);
+    byte_24E[13] = (((_m24E.ACC_AccTrqReq & (0x1FU))<<3))| ((_m24E.ACC_AccTrqReqActive & (0x01U)) << 2);
+
+    if(decition.leftlamp() == true && decition.rightlamp() == false)
+        _m25E.ADS_UDLCTurnLightReq = 3;
+    else if(decition.leftlamp() == false && decition.rightlamp() == true)
+        _m25E.ADS_UDLCTurnLightReq = 4;
+    else
+        _m25E.ADS_UDLCTurnLightReq = 0;
+
+    byte_25E[3] = ((_m25E.ADS_UDLCTurnLightReq & (0x07U)));
+
+}
+
+
+void adc_controller_shenlan_v2_core::ExecSend()
+{
+    static int nCount = 0;
+    nCount++;
+
+    auto xmsg = adc_autoware_msgs::msg::AdcCanMsgs();
+    auto xraw = adc_autoware_msgs::msg::AdcCanFrame();
+
+    int64_t nnow = std::chrono::system_clock::now().time_since_epoch().count();
+    xraw.header.frame_id = "adc";
+    xraw.header.stamp.sec = nnow/1e9;
+    xraw.header.stamp.nanosec = nnow - xraw.header.stamp.sec * 1e9;
+    xraw.id = 0x1C4;
+    memcpy(xraw.data.data(),byte_1C4,32);
+    xraw.dlc = 32;
+    xraw.is_error = false;
+    xraw.is_extended = false;
+    xraw.is_rtr = false;
+    xmsg.frames.push_back(xraw);
+
+    nnow = std::chrono::system_clock::now().time_since_epoch().count();
+    xraw.header.frame_id = "adc";
+    xraw.header.stamp.sec = nnow/1e9;
+    xraw.header.stamp.nanosec = nnow - xraw.header.stamp.sec * 1e9;
+    xraw.id = 0x24E;
+    memcpy(xraw.data.data(),byte_24E,32);
+    xraw.dlc = 64;
+    xraw.is_error = false;
+    xraw.is_extended = false;
+    xraw.is_rtr = false;
+    xmsg.frames.push_back(xraw);
+    if(nCount%2 == 1)
+    {
+        xmsg.frames.push_back(xraw);
+    }
+
+    nnow = std::chrono::system_clock::now().time_since_epoch().count();
+    xraw.header.frame_id = "adc";
+    xraw.header.stamp.sec = nnow/1e9;
+    xraw.header.stamp.nanosec = nnow - xraw.header.stamp.sec * 1e9;
+    xraw.id = 0x25E;
+    memcpy(xraw.data.data(),byte_25E,32);
+    xraw.dlc = 32;
+    xraw.is_error = false;
+    xraw.is_extended = false;
+    xraw.is_rtr = false;
+    xmsg.frames.push_back(xraw);
+    if(nCount%2 == 1)
+    {
+        xmsg.frames.push_back(xraw);
+    }
+
+
+    nnow = std::chrono::system_clock::now().time_since_epoch().count();
+    xmsg.header.frame_id = "adc";
+    xmsg.header.stamp.sec = nnow/1e9;
+    xmsg.header.stamp.nanosec = nnow - xraw.header.stamp.sec * 1e9;
+
+    pub_msgs_cansend0->publish(xmsg);
+
+}
+
+
+void adc_controller_shenlan_v2_core::Activate()
+{
+    std::this_thread::sleep_for(std::chrono::milliseconds(100));
+    iv::brain::decition xdecition;
+    xdecition.set_brake(0.0);
+    xdecition.set_torque(0.0);
+//    for(int j=0;j<100000;j++)
+//    {
+        std::cout<<" run "<<std::endl;
+    for(int i = 0; i < 3; i++){
+        xdecition.set_wheelangle(0.0);
+        xdecition.set_angle_mode(0);
+        xdecition.set_angle_active(0);
+        xdecition.set_acc_active(0);
+        xdecition.set_brake_active(0);
+//        xdecition.set_brake_type(0);
+        xdecition.set_auto_mode(0);
+        gnState = 0;
+        executeDecition(xdecition);
+        ExecSend();
+        std::this_thread::sleep_for(std::chrono::milliseconds(10));
+    }
+    for(int i = 0; i < 3; i++){
+        xdecition.set_wheelangle(0.0);
+        xdecition.set_angle_mode(1);
+        xdecition.set_angle_active(1);
+        xdecition.set_acc_active(1);
+        xdecition.set_brake_active(1);
+//        xdecition.set_brake_type(1);
+        xdecition.set_auto_mode(3);
+        gnState = 1;
+        executeDecition(xdecition);
+        ExecSend();
+        std::this_thread::sleep_for(std::chrono::milliseconds(10));
+    }
+//    }
+}
+
+void adc_controller_shenlan_v2_core::UnAcitvate()
+{
+    iv::brain::decition xdecition;
+
+    xdecition.set_brake(0.0);
+    xdecition.set_torque(0.0);
+    for(int i = 0; i < 3; i++){
+        xdecition.set_wheelangle(0);
+        xdecition.set_angle_mode(1);
+        xdecition.set_angle_active(1);
+        xdecition.set_acc_active(1);
+        xdecition.set_brake_active(1);
+//        xdecition.set_brake_type(1);
+        xdecition.set_auto_mode(3);
+        gnState = 1;
+        executeDecition(xdecition);
+        ExecSend();
+        std::this_thread::sleep_for(std::chrono::milliseconds(10));
+    }
+    for(int i = 0; i < 3; i++){
+        xdecition.set_wheelangle(0);
+        xdecition.set_angle_mode(0);
+        xdecition.set_angle_active(0);
+        xdecition.set_acc_active(0);
+        xdecition.set_brake_active(0);
+//        xdecition.set_brake_type(0);
+        gnState = 0;
+        xdecition.set_auto_mode(0);
+        executeDecition(xdecition);
+        ExecSend();
+        std::this_thread::sleep_for(std::chrono::milliseconds(10));
+    }
+}
+
+void adc_controller_shenlan_v2_core::initial()
+{
+    for (uint8_t i = 0; i < 64; i++) //CAN  to  canfd
+    {
+        byte_1C4[i] = 0;
+        byte_24E[i] = 0;
+        //byte_36E[i] = 0;
+    }
+}
+
+
+
+
+

+ 17 - 0
src/ros2/src/adc_controller_shenlan_v2/src/adc_controller_shenlan_v2_node.cpp

@@ -0,0 +1,17 @@
+
+
+#include <rclcpp/rclcpp.hpp>
+
+#include <memory>
+
+#include "adc_controller_shenlan_v2/adc_controller_shenlan_v2_core.hpp"
+
+int main(int argc, char ** argv)
+{
+  rclcpp::init(argc, argv);
+
+  rclcpp::spin(std::make_shared<adc_controller_shenlan_v2_core>());
+  rclcpp::shutdown();
+
+  return 0;
+}

+ 487 - 0
src/ros2/src/adc_controller_shenlan_v2/src/control_status.cpp

@@ -0,0 +1,487 @@
+#include <adc_controller_shenlan_v2/control_status.h>
+
+
+
+
+
+//#if 1
+
+
+void iv::control::ControlStatus::set_cmd_checksum(unsigned char cmd_id)
+{
+    unsigned int check_sum=0;
+    if(cmd_id==0x10)
+    {
+        for(int i=0;i<7;i++)
+        {
+            check_sum^=(ServiceControlStatus.command10.byte[i]);
+        }
+        ServiceControlStatus.command10.byte[7]=check_sum;
+    }else if(cmd_id==0x11)
+    {
+        for(int i=0;i<7;i++)
+        {
+            check_sum^=(ServiceControlStatus.command11.byte[i]);
+        }
+        ServiceControlStatus.command11.byte[7]=check_sum;
+    }else if(cmd_id==0x12)
+    {
+        for(int i=0;i<7;i++)
+        {
+            check_sum^=(ServiceControlStatus.command12.byte[i]);
+        }
+        ServiceControlStatus.command12.byte[7]=check_sum;
+    }
+}
+
+
+
+
+void iv::control::ControlStatus::set_wheel_angle(float angle)
+{
+
+    int ang =(angle+870)*10;
+    ServiceControlStatus.command12.bit.ang_H = (ang)  /256;
+    ServiceControlStatus.command12.bit.ang_L = (ang)  % 256;
+}
+
+
+
+void iv::control::ControlStatus::set_wheel_speed(float speed)
+{
+
+    int angSpeed =speed;
+    ServiceControlStatus.command12.bit.ang_speed = angSpeed;
+}
+
+void iv::control::ControlStatus::set_wheel_enable(bool enable)
+{
+
+    if(enable){
+        ServiceControlStatus.command12.bit.ang_enable = 1;
+    }else{
+        ServiceControlStatus.command12.bit.ang_enable = 0;
+    }
+}
+
+
+
+
+ void iv::control::ControlStatus::set_speed_limit(float speed)
+ {
+     ServiceControlStatus.command11.bit.speed_limit = (unsigned)speed;
+ }
+
+
+
+void iv::control::ControlStatus::set_aeb(float aeb)
+{
+    int aebBrake =(aeb+16)/0.000488;
+    ServiceControlStatus.command11.bit.aeb_H = (aebBrake)  /256;
+    ServiceControlStatus.command11.bit.aeb_L = (aebBrake)  % 256;
+}
+
+void iv::control::ControlStatus::set_torque(float troque)
+{
+    command11.bit.torque=(unsigned)(troque*2.5);
+}
+
+void iv::control::ControlStatus::set_brake(float brake)
+{
+    command11.bit.brake=(unsigned)brake;
+}
+
+
+
+void iv::control::ControlStatus::set_gear(int gear)
+{
+    command11.bit.gear = (unsigned)gear;
+}
+
+void iv::control::ControlStatus::set_handBrake(bool handbrake)
+{
+    if(handbrake){
+        command11.bit.park = 2;
+    }else{
+        command11.bit.park = 1;
+    }
+}
+
+void iv::control::ControlStatus::set_driveMode(char driveMode)
+{
+    command11.bit.driveMode = (unsigned)driveMode;
+}
+
+void iv::control::ControlStatus::set_gear_enable(bool enable){
+    if (enable == true)
+        command11.bit.gear_enable = 1;
+    else
+        command11.bit.gear_enable = 0;
+}
+
+void iv::control::ControlStatus::set_acc_enable(bool enable){
+    if (enable == true)
+        command11.bit.acc_enable = 1;
+    else
+        command11.bit.acc_enable = 0;
+}
+
+void iv::control::ControlStatus::set_aeb_enable(bool enable){
+    if (enable == true)
+        command11.bit.aeb_enable = 1;
+    else
+        command11.bit.aeb_enable = 0;
+}
+
+
+//void iv::control::ControlStatus::set_win_lf(char para)
+//{
+//    command10.bit.windowlf = (unsigned)para;
+//}
+
+//void iv::control::ControlStatus::set_win_rf(char para)
+//{
+//    command10.bit.windowrf = (unsigned)para;
+//}
+
+//void iv::control::ControlStatus::set_win_lr(char para)
+//{
+//    command10.bit.windowlr = (unsigned)para;
+//}
+
+//void iv::control::ControlStatus::set_win_rr(char para)
+//{
+//    command10.bit.windowrr = (unsigned)para;
+//}
+
+//空调控制
+void iv::control::ControlStatus::set_air_on(char para)
+{
+    command10.bit.air_on = (unsigned)para;
+}
+
+
+
+//void iv::control::ControlStatus::set_air_cricle(char para)
+//{
+//    command10.bit.air_cricle = (unsigned)para;
+//}
+
+
+//void iv::control::ControlStatus::set_air_auto(char para)
+//{
+//    command10.bit.air_auto = (unsigned)para;
+//}
+
+
+//void iv::control::ControlStatus::set_air_off(char para)
+//{
+//    command10.bit.air_off = (unsigned)para;
+//}
+
+
+//void iv::control::ControlStatus::set_air_temup(char para)
+//{
+//    command10.bit.tem_up = (unsigned)para;
+//}
+
+
+//void iv::control::ControlStatus::set_air_temdown(char para)
+//{
+//    command10.bit.tem_down = (unsigned)para;
+//}
+
+
+//void iv::control::ControlStatus::set_air_powerup(char para)
+//{
+//    command10.bit.power_up = (unsigned)para;
+//}
+
+
+//void iv::control::ControlStatus::set_air_powerdown(char para)
+//{
+//    command10.bit.power_down = (unsigned)para;
+//}
+
+
+void iv::control::ControlStatus::set_obligate(char para)
+{
+    command10.bit.ignition = (unsigned)para;
+}
+
+
+void iv::control::ControlStatus::set_door(char enable)
+{
+    command10.bit.door = (unsigned)enable;
+}
+
+
+void iv::control::ControlStatus::set_turnsignals_control(bool left, bool right)
+{
+    if ( (left == true) && (right == false) )
+    {
+        command10.bit.turn_light = 0x01;
+    }
+    else if ( (left == false) && (right == true) )
+    {
+        command10.bit.turn_light = 0x02;
+    }
+    else if ((left == false) && (right == false))
+    {
+        command10.bit.turn_light = 0x00;
+    }
+    else
+    {
+        command10.bit.turn_light = 0x03;
+    }
+}
+
+
+void iv::control::ControlStatus::set_small_light(char para)
+{
+    command10.bit.small_light = (unsigned)para;
+}
+
+
+void iv::control::ControlStatus::set_near_light(char para)
+{
+    command10.bit.near_light = (unsigned)para;
+}
+
+
+void iv::control::ControlStatus::set_horn(char para)
+{
+    command10.bit.horn = (unsigned)para;
+}
+
+
+void iv::control::ControlStatus::set_far_light(char para)
+{
+    command10.bit.far_light = (unsigned)para;
+}
+
+
+void iv::control::ControlStatus::set_frog_light(char para)
+{
+    command10.bit.fog_light = (unsigned)para;
+}
+
+
+void iv::control::ControlStatus::set_wiper(char para)
+{
+    command10.bit.wiper = (unsigned)para;
+}
+
+
+void iv::control::ControlStatus::set_brake_light(char para)
+{
+    command10.bit.brake_light = (unsigned)para;
+}
+
+
+void iv::control::ControlStatus::set_defrog(char para)
+{
+    command10.bit.defrog = (unsigned)para;
+}
+
+
+void iv::control::ControlStatus::set_reverse_light(char para)
+{
+    command10.bit.revers_light = (unsigned)para;
+}
+
+
+void set_air_temp(char para);
+void set_air_mode(char para);
+void set_air_enable(bool enable);
+void set_wind_level(char para);
+void set_roof_light(char para);
+void set_home_light(char para);
+void set_air_worktime(char para);
+void set_air_offtime(char para);
+
+void iv::control::ControlStatus::set_air_temp(char para)
+{
+    command10.bit.air_temp = (unsigned)para+40;
+}
+
+
+void iv::control::ControlStatus::set_air_mode(char para)
+{
+    command10.bit.air_mode = (unsigned)para;
+}
+
+void iv::control::ControlStatus::set_air_enable(bool enable)
+{
+    if(enable){
+        command10.bit.air_enable = 0x01;
+    }else{
+        command10.bit.air_enable = 0x00;
+    }
+}
+
+void iv::control::ControlStatus::set_wind_level(char para)
+{
+    command10.bit.air_wind_level = (unsigned)para;
+}
+
+void iv::control::ControlStatus::set_roof_light(char para)
+{
+    command10.bit.roof_light = (unsigned)para;
+}
+
+void iv::control::ControlStatus::set_home_light(char para)
+{
+    command10.bit.home_light = (unsigned)para;
+}
+
+void iv::control::ControlStatus::set_air_worktime(char para)
+{
+    command10.bit.air_work_time = (unsigned)para;
+}
+
+
+void iv::control::ControlStatus::set_air_offtime(char para)
+{
+    command10.bit.air_off_time = (unsigned)para;
+}
+
+
+//void iv::control::ControlStatus::set_speaker(bool enable){
+//    if (enable == true)
+//        command.bit.speaker = 1;
+//    else
+//        command.bit.speaker = 0;
+//}
+
+//void iv::control::ControlStatus::set_door(char enable){
+//    if (enable == true)
+//        command.bit.door = 1;
+//    else
+//        command.bit.door = 0;
+//}
+
+//void iv::control::ControlStatus::set_doorEnable(bool enable){
+//    if (enable == true){
+//        command.bit.doorEnable = 1;
+//        command.bit.door=1;
+//    }
+//    else{
+//        command.bit.doorEnable = 0;
+//        command.bit.door=0;
+//    }
+//}
+
+////void iv::control::ControlStatus::set_flicker(bool enable){
+////    if (enable == true)
+////        command.bit.flicker = 1;
+////    else
+////        command.bit.flicker = 0;
+////}
+//void iv::control::ControlStatus::set_light(bool enable){
+//    if (enable == true)
+//       command.bit.bright = 1;
+//    else
+//       command.bit.bright = 0;
+//}
+
+//void iv::control::ControlStatus::set_leftlight(bool enable){
+//    if (enable == true)
+//       command.bit.left_turn = 1;
+//    else
+//       command.bit.left_turn = 0;
+//}
+
+
+//void iv::control::ControlStatus::set_rightlight(bool enable){
+//    if (enable == true)
+//       command.bit.right_turn = 1;
+//    else
+//       command.bit.right_turn = 0;
+//}
+
+
+
+
+
+
+//void iv::control::ControlStatus::set_turnsignals_control(bool left, bool right){
+//    if (left == true)
+//    {
+//        command.bit.left_turn = 1;
+//        command.bit.right_turn = 0;
+//    }
+//    else if (right == true)
+//    {
+//        command.bit.left_turn = 0;
+//        command.bit.right_turn = 1;
+//    }
+//    else
+//    {
+//        command.bit.left_turn = 0;
+//        command.bit.right_turn = 0;
+//    }
+//}
+
+
+
+
+
+
+
+
+//#else
+
+//void iv::control::ControlStatus::set_accelerate(float percent)
+//{
+//    command.bit.acce = (unsigned)((percent + 7) * 20);
+//}
+//void iv::control::ControlStatus::set_wheel_angle(float angle)
+//{
+//    command.bit.ang_H = angle * 10 >> 8;
+
+//    command.bit.ang_L = angle * 10 % 256;
+//}
+//void iv::control::ControlStatus::set_engine(char enable)
+//{
+//    command.bit.engine = enable;
+//}
+//void iv::control::ControlStatus::set_door(char enable){
+//    command.bit.door = enable;
+//}
+//void iv::control::ControlStatus::set_speaker(bool enable){
+//    if (enable == true)
+//        command.bit.speaker = 1;
+//    else
+//        command.bit.speaker = 0;
+//}
+//void iv::control::ControlStatus::set_flicker(bool enable){
+//    if (enable == true)
+//        command.bit.flicker = 1;
+//    else
+//        command.bit.flicker = 0;
+//}
+//void iv::control::ControlStatus::set_light(bool enable){
+//    if (enable == true)
+//       command.bit.bright = 1;
+//    else
+//       command.bit.bright = 0;
+//}
+//void iv::control::ControlStatus::set_turnsignals_control(bool left, bool right){
+//    if (left == true)
+//    {
+//        command.bit.left_turn = 1;
+//        command.bit.right_turn = 0;
+//    }
+//    else if (right == true)
+//    {
+//        command.bit.left_turn = 0;
+//        command.bit.right_turn = 1;
+//    }
+//    else
+//    {
+//        command.bit.left_turn = 0;
+//        command.bit.right_turn = 0;
+//    }
+//}
+//#endif

+ 204 - 0
src/ros2/src/adc_controller_shenlan_v2/src/controller.cpp

@@ -0,0 +1,204 @@
+#include "adc_controller_shenlan_v2/controller.h"
+
+iv::control::Controller::Controller() {
+
+}
+
+iv::control::Controller::~Controller() {
+
+}
+
+void iv::control::Controller::inialize() {
+
+}
+
+
+
+
+
+//校验和
+void iv::control::Controller::cmd_checksum(unsigned char cmd_id) {
+    ServiceControlStatus.set_cmd_checksum(cmd_id);
+}
+//方向盘控制
+void iv::control::Controller::control_wheel(float angle) {
+    ServiceControlStatus.set_wheel_angle(angle);
+}
+
+void iv::control::Controller:: control_angle_speed(float angSpeed){
+    ServiceControlStatus.set_wheel_speed(angSpeed);
+}
+
+void iv::control::Controller:: control_angle_enable(bool enable){
+    ServiceControlStatus.set_wheel_enable(enable);
+}
+//速度限制
+void iv::control::Controller:: control_speed_limit(float speedLimit){
+    ServiceControlStatus.set_speed_limit(speedLimit);
+}
+//油门控制
+void iv::control::Controller::control_torque(float percent){
+    ServiceControlStatus.set_torque(percent);
+}
+void iv::control::Controller::control_acc_en(bool enanble){
+    ServiceControlStatus.set_acc_enable(enanble);
+}
+
+
+void iv::control::Controller::control_aeb(float aeb){
+    ServiceControlStatus.set_aeb(aeb);
+}
+void iv::control::Controller::control_aeb_en(bool enable){
+    ServiceControlStatus.set_aeb_enable(enable);
+}
+//刹车控制
+void iv::control::Controller::control_brake(float brake){
+    ServiceControlStatus.set_brake(brake);
+}
+//档位控制
+void iv::control::Controller::control_gear(float gear){
+    ServiceControlStatus.set_gear(gear);
+}
+void iv::control::Controller::control_gear_en(bool enable){
+    ServiceControlStatus.set_gear_enable(enable);
+}
+//手刹
+void iv::control::Controller::control_handBrake(bool  enable){
+    ServiceControlStatus.set_handBrake(enable);
+}
+//驾驶模式
+void iv::control::Controller::control_mode(char mode){
+    ServiceControlStatus.set_driveMode(mode);
+}
+//车窗控制
+//void iv::control::Controller::control_win_lf(char para){
+//     ServiceControlStatus.set_win_lf(para);
+//}
+//void iv::control::Controller::control_win_rf(char para){
+//     ServiceControlStatus.set_win_rf(para);
+//}
+
+//void iv::control::Controller::control_win_lr(char para){
+//     ServiceControlStatus.set_win_lr(para);
+//}
+
+//void iv::control::Controller::control_win_rr(char para){
+//     ServiceControlStatus.set_win_rr(para);
+//}
+
+//空调控制
+void iv::control::Controller::control_air_on(bool enable){
+    if(enable){
+        ServiceControlStatus.set_air_on(1);
+    }else{
+        ServiceControlStatus.set_air_on(0);
+    }
+}
+//void iv::control::Controller::control_air_cricle(char para){
+//     ServiceControlStatus.set_air_cricle(para);
+//}
+//void iv::control::Controller::control_air_auto(char para){
+//     ServiceControlStatus.set_air_auto(para);
+//}
+//void iv::control::Controller::control_air_off(char para){
+//     ServiceControlStatus.set_air_off(para);
+//}
+//void iv::control::Controller::control_air_temup(char para){
+//     ServiceControlStatus.set_air_temup(para);
+//}
+//void iv::control::Controller::control_air_temdown(char para){
+//     ServiceControlStatus.set_air_temdown(para);
+//}
+//void iv::control::Controller::control_air_powerup(char para){
+//     ServiceControlStatus.set_air_powerup(para);
+//}
+//void iv::control::Controller::control_air_powerdown(char para){
+//     ServiceControlStatus.set_air_powerdown(para);
+//}
+//点火控制
+void iv::control::Controller::control_obligate(char para){
+    ServiceControlStatus.set_obligate(para);
+}
+//车门控制
+void iv::control::Controller::control_door(char enable){
+    ServiceControlStatus.set_door(enable);
+}
+//车灯控制
+void iv::control::Controller::control_turnsignals(bool left, bool right){
+    ServiceControlStatus.set_turnsignals_control(left,right);
+}
+void iv::control::Controller::control_small_light(char para){
+    ServiceControlStatus.set_small_light(para);
+}
+void iv::control::Controller::control_near_light(char para){
+    ServiceControlStatus.set_near_light(para);
+}
+
+void iv::control::Controller::control_far_light(char para){
+    ServiceControlStatus.set_far_light(para);
+}
+void iv::control::Controller::control_frog_light(char para){
+    ServiceControlStatus.set_frog_light(para);
+}
+void iv::control::Controller::control_brake_light(char para){
+    ServiceControlStatus.set_brake_light(para);
+}
+void iv::control::Controller::control_defrog(char para){
+    ServiceControlStatus.set_defrog(para);
+}
+void iv::control::Controller::control_reverse_light(char para){
+    ServiceControlStatus.set_reverse_light(para);
+}
+
+//喇叭控制
+void iv::control::Controller::control_horn(char para){
+    ServiceControlStatus.set_horn(para);
+}
+//雨刷控制
+void iv::control::Controller::control_wiper(char para){
+    ServiceControlStatus.set_wiper(para);
+}
+
+
+void iv::control::Controller::control_air_temp(char para){
+    ServiceControlStatus.set_air_temp(para);
+}
+
+void iv::control::Controller::control_air_mode(char para){
+    ServiceControlStatus.set_air_mode(para);
+}
+
+void iv::control::Controller::control_air_enable(bool enable){
+    ServiceControlStatus.set_air_enable(enable);
+}
+
+void iv::control::Controller::control_wind_level(char para){
+    ServiceControlStatus.set_wind_level(para);
+}
+
+void iv::control::Controller::control_roof_light(char para){
+    ServiceControlStatus.set_roof_light(para);
+}
+
+void iv::control::Controller::control_home_light(char para){
+    ServiceControlStatus.set_home_light(para);
+}
+
+void iv::control::Controller::control_air_worktime(char para){
+    ServiceControlStatus.set_air_worktime(para);
+}
+
+void iv::control::Controller::control_air_offtime(char para){
+    ServiceControlStatus.set_air_offtime(para);
+}
+
+
+
+
+
+//void iv::control::Controller::control_flicker(bool enable){
+//    ServiceControlStatus.set_flicker(enable);
+//}
+//void iv::control::Controller::control_braking(float percent){
+
+//}

+ 1795 - 0
src/ros2/src/adc_controller_shenlan_v2/src/decition.pb.cc

@@ -0,0 +1,1795 @@
+// Generated by the protocol buffer compiler.  DO NOT EDIT!
+// source: decition.proto
+
+#include "decition.pb.h"
+
+#include <algorithm>
+
+#include <google/protobuf/io/coded_stream.h>
+#include <google/protobuf/extension_set.h>
+#include <google/protobuf/wire_format_lite.h>
+#include <google/protobuf/descriptor.h>
+#include <google/protobuf/generated_message_reflection.h>
+#include <google/protobuf/reflection_ops.h>
+#include <google/protobuf/wire_format.h>
+// @@protoc_insertion_point(includes)
+#include <google/protobuf/port_def.inc>
+namespace iv {
+namespace brain {
+class decitionDefaultTypeInternal {
+ public:
+  ::PROTOBUF_NAMESPACE_ID::internal::ExplicitlyConstructed<decition> _instance;
+} _decition_default_instance_;
+}  // namespace brain
+}  // namespace iv
+static void InitDefaultsscc_info_decition_decition_2eproto() {
+  GOOGLE_PROTOBUF_VERIFY_VERSION;
+
+  {
+    void* ptr = &::iv::brain::_decition_default_instance_;
+    new (ptr) ::iv::brain::decition();
+    ::PROTOBUF_NAMESPACE_ID::internal::OnShutdownDestroyMessage(ptr);
+  }
+  ::iv::brain::decition::InitAsDefaultInstance();
+}
+
+::PROTOBUF_NAMESPACE_ID::internal::SCCInfo<0> scc_info_decition_decition_2eproto =
+    {{ATOMIC_VAR_INIT(::PROTOBUF_NAMESPACE_ID::internal::SCCInfoBase::kUninitialized), 0, 0, InitDefaultsscc_info_decition_decition_2eproto}, {}};
+
+static ::PROTOBUF_NAMESPACE_ID::Metadata file_level_metadata_decition_2eproto[1];
+static constexpr ::PROTOBUF_NAMESPACE_ID::EnumDescriptor const** file_level_enum_descriptors_decition_2eproto = nullptr;
+static constexpr ::PROTOBUF_NAMESPACE_ID::ServiceDescriptor const** file_level_service_descriptors_decition_2eproto = nullptr;
+
+const ::PROTOBUF_NAMESPACE_ID::uint32 TableStruct_decition_2eproto::offsets[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = {
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, _has_bits_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, _internal_metadata_),
+  ~0u,  // no _extensions_
+  ~0u,  // no _oneof_case_
+  ~0u,  // no _weak_field_map_
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, speed_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, wheelangle_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, wheelspeed_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, lateraltorque_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, brake_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, accelerator_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, torque_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, leftlamp_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, rightlamp_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, doublespark_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, headlight_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, highbeam_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, dippedlight_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, taillight_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, domelight_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, foglamp_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, backuplight_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, brakelamp_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, engine_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, mode_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, handbrake_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, speak_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, door_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, gear_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, wiper_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, grade_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, ttc_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, air_enable_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, air_temp_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, air_mode_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, wind_level_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, roof_light_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, home_light_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, air_worktime_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, air_offtime_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, air_on_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, air_ac_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, air_circle_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, air_auto_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, air_off_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, window_fl_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, window_fr_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, window_rl_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, window_rr_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, angle_mode_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, angle_active_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, acc_active_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, brake_active_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, brake_type_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, niuju_y_),
+  PROTOBUF_FIELD_OFFSET(::iv::brain::decition, auto_mode_),
+  0,
+  1,
+  2,
+  3,
+  4,
+  5,
+  6,
+  7,
+  8,
+  9,
+  10,
+  12,
+  11,
+  13,
+  14,
+  15,
+  19,
+  20,
+  16,
+  17,
+  18,
+  21,
+  23,
+  24,
+  25,
+  26,
+  27,
+  22,
+  28,
+  29,
+  30,
+  31,
+  32,
+  33,
+  34,
+  35,
+  36,
+  37,
+  38,
+  39,
+  40,
+  41,
+  42,
+  43,
+  44,
+  45,
+  46,
+  47,
+  48,
+  49,
+  50,
+};
+static const ::PROTOBUF_NAMESPACE_ID::internal::MigrationSchema schemas[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = {
+  { 0, 56, sizeof(::iv::brain::decition)},
+};
+
+static ::PROTOBUF_NAMESPACE_ID::Message const * const file_default_instances[] = {
+  reinterpret_cast<const ::PROTOBUF_NAMESPACE_ID::Message*>(&::iv::brain::_decition_default_instance_),
+};
+
+const char descriptor_table_protodef_decition_2eproto[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) =
+  "\n\016decition.proto\022\010iv.brain\"\264\007\n\010decition\022"
+  "\r\n\005speed\030\001 \001(\002\022\022\n\nwheelAngle\030\002 \001(\002\022\022\n\nwh"
+  "eelSpeed\030\003 \001(\002\022\025\n\rlateralTorque\030\004 \001(\002\022\r\n"
+  "\005brake\030\005 \001(\002\022\023\n\013accelerator\030\006 \001(\002\022\016\n\006tor"
+  "que\030\007 \001(\002\022\020\n\010leftLamp\030\010 \001(\010\022\021\n\trightLamp"
+  "\030\t \001(\010\022\023\n\013doubleSpark\030\n \001(\010\022\021\n\theadLight"
+  "\030\013 \001(\010\022\020\n\010highBeam\030\014 \001(\010\022\023\n\013dippedLight\030"
+  "\r \001(\005\022\021\n\ttailLight\030\016 \001(\010\022\021\n\tdomeLight\030\017 "
+  "\001(\010\022\017\n\007fogLamp\030\020 \001(\010\022\023\n\013backupLight\030\021 \001("
+  "\010\022\021\n\tbrakeLamp\030\022 \001(\010\022\016\n\006engine\030\023 \001(\005\022\014\n\004"
+  "mode\030\024 \001(\005\022\021\n\thandBrake\030\025 \001(\005\022\r\n\005speak\030\026"
+  " \001(\010\022\014\n\004door\030\027 \001(\005\022\014\n\004gear\030\030 \001(\005\022\r\n\005wipe"
+  "r\030\031 \001(\005\022\r\n\005grade\030\032 \001(\005\022\013\n\003ttc\030\033 \001(\002\022\022\n\na"
+  "ir_enable\030\034 \001(\010\022\020\n\010air_temp\030\035 \001(\002\022\020\n\010air"
+  "_mode\030\036 \001(\002\022\022\n\nwind_level\030\037 \001(\002\022\022\n\nroof_"
+  "light\030  \001(\005\022\022\n\nhome_light\030! \001(\005\022\024\n\014air_w"
+  "orktime\030\" \001(\002\022\023\n\013air_offtime\030# \001(\002\022\016\n\006ai"
+  "r_on\030$ \001(\010\022\016\n\006air_ac\030% \001(\010\022\022\n\nair_circle"
+  "\030& \001(\010\022\020\n\010air_auto\030\' \001(\010\022\017\n\007air_off\030( \001("
+  "\010\022\021\n\twindow_fl\030) \001(\r\022\021\n\twindow_fr\030* \001(\r\022"
+  "\021\n\twindow_rl\030+ \001(\r\022\021\n\twindow_rr\030, \001(\r\022\022\n"
+  "\nangle_mode\030- \001(\r\022\024\n\014angle_active\030. \001(\r\022"
+  "\022\n\nacc_active\030/ \001(\r\022\024\n\014brake_active\0300 \001("
+  "\r\022\022\n\nbrake_type\0301 \001(\r\022\017\n\007niuju_y\0302 \001(\002\022\021"
+  "\n\tauto_mode\0303 \001(\r"
+  ;
+static const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable*const descriptor_table_decition_2eproto_deps[1] = {
+};
+static ::PROTOBUF_NAMESPACE_ID::internal::SCCInfoBase*const descriptor_table_decition_2eproto_sccs[1] = {
+  &scc_info_decition_decition_2eproto.base,
+};
+static ::PROTOBUF_NAMESPACE_ID::internal::once_flag descriptor_table_decition_2eproto_once;
+const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable descriptor_table_decition_2eproto = {
+  false, false, descriptor_table_protodef_decition_2eproto, "decition.proto", 977,
+  &descriptor_table_decition_2eproto_once, descriptor_table_decition_2eproto_sccs, descriptor_table_decition_2eproto_deps, 1, 0,
+  schemas, file_default_instances, TableStruct_decition_2eproto::offsets,
+  file_level_metadata_decition_2eproto, 1, file_level_enum_descriptors_decition_2eproto, file_level_service_descriptors_decition_2eproto,
+};
+
+// Force running AddDescriptors() at dynamic initialization time.
+static bool dynamic_init_dummy_decition_2eproto = (static_cast<void>(::PROTOBUF_NAMESPACE_ID::internal::AddDescriptors(&descriptor_table_decition_2eproto)), true);
+namespace iv {
+namespace brain {
+
+// ===================================================================
+
+void decition::InitAsDefaultInstance() {
+}
+class decition::_Internal {
+ public:
+  using HasBits = decltype(std::declval<decition>()._has_bits_);
+  static void set_has_speed(HasBits* has_bits) {
+    (*has_bits)[0] |= 1u;
+  }
+  static void set_has_wheelangle(HasBits* has_bits) {
+    (*has_bits)[0] |= 2u;
+  }
+  static void set_has_wheelspeed(HasBits* has_bits) {
+    (*has_bits)[0] |= 4u;
+  }
+  static void set_has_lateraltorque(HasBits* has_bits) {
+    (*has_bits)[0] |= 8u;
+  }
+  static void set_has_brake(HasBits* has_bits) {
+    (*has_bits)[0] |= 16u;
+  }
+  static void set_has_accelerator(HasBits* has_bits) {
+    (*has_bits)[0] |= 32u;
+  }
+  static void set_has_torque(HasBits* has_bits) {
+    (*has_bits)[0] |= 64u;
+  }
+  static void set_has_leftlamp(HasBits* has_bits) {
+    (*has_bits)[0] |= 128u;
+  }
+  static void set_has_rightlamp(HasBits* has_bits) {
+    (*has_bits)[0] |= 256u;
+  }
+  static void set_has_doublespark(HasBits* has_bits) {
+    (*has_bits)[0] |= 512u;
+  }
+  static void set_has_headlight(HasBits* has_bits) {
+    (*has_bits)[0] |= 1024u;
+  }
+  static void set_has_highbeam(HasBits* has_bits) {
+    (*has_bits)[0] |= 4096u;
+  }
+  static void set_has_dippedlight(HasBits* has_bits) {
+    (*has_bits)[0] |= 2048u;
+  }
+  static void set_has_taillight(HasBits* has_bits) {
+    (*has_bits)[0] |= 8192u;
+  }
+  static void set_has_domelight(HasBits* has_bits) {
+    (*has_bits)[0] |= 16384u;
+  }
+  static void set_has_foglamp(HasBits* has_bits) {
+    (*has_bits)[0] |= 32768u;
+  }
+  static void set_has_backuplight(HasBits* has_bits) {
+    (*has_bits)[0] |= 524288u;
+  }
+  static void set_has_brakelamp(HasBits* has_bits) {
+    (*has_bits)[0] |= 1048576u;
+  }
+  static void set_has_engine(HasBits* has_bits) {
+    (*has_bits)[0] |= 65536u;
+  }
+  static void set_has_mode(HasBits* has_bits) {
+    (*has_bits)[0] |= 131072u;
+  }
+  static void set_has_handbrake(HasBits* has_bits) {
+    (*has_bits)[0] |= 262144u;
+  }
+  static void set_has_speak(HasBits* has_bits) {
+    (*has_bits)[0] |= 2097152u;
+  }
+  static void set_has_door(HasBits* has_bits) {
+    (*has_bits)[0] |= 8388608u;
+  }
+  static void set_has_gear(HasBits* has_bits) {
+    (*has_bits)[0] |= 16777216u;
+  }
+  static void set_has_wiper(HasBits* has_bits) {
+    (*has_bits)[0] |= 33554432u;
+  }
+  static void set_has_grade(HasBits* has_bits) {
+    (*has_bits)[0] |= 67108864u;
+  }
+  static void set_has_ttc(HasBits* has_bits) {
+    (*has_bits)[0] |= 134217728u;
+  }
+  static void set_has_air_enable(HasBits* has_bits) {
+    (*has_bits)[0] |= 4194304u;
+  }
+  static void set_has_air_temp(HasBits* has_bits) {
+    (*has_bits)[0] |= 268435456u;
+  }
+  static void set_has_air_mode(HasBits* has_bits) {
+    (*has_bits)[0] |= 536870912u;
+  }
+  static void set_has_wind_level(HasBits* has_bits) {
+    (*has_bits)[0] |= 1073741824u;
+  }
+  static void set_has_roof_light(HasBits* has_bits) {
+    (*has_bits)[0] |= 2147483648u;
+  }
+  static void set_has_home_light(HasBits* has_bits) {
+    (*has_bits)[1] |= 1u;
+  }
+  static void set_has_air_worktime(HasBits* has_bits) {
+    (*has_bits)[1] |= 2u;
+  }
+  static void set_has_air_offtime(HasBits* has_bits) {
+    (*has_bits)[1] |= 4u;
+  }
+  static void set_has_air_on(HasBits* has_bits) {
+    (*has_bits)[1] |= 8u;
+  }
+  static void set_has_air_ac(HasBits* has_bits) {
+    (*has_bits)[1] |= 16u;
+  }
+  static void set_has_air_circle(HasBits* has_bits) {
+    (*has_bits)[1] |= 32u;
+  }
+  static void set_has_air_auto(HasBits* has_bits) {
+    (*has_bits)[1] |= 64u;
+  }
+  static void set_has_air_off(HasBits* has_bits) {
+    (*has_bits)[1] |= 128u;
+  }
+  static void set_has_window_fl(HasBits* has_bits) {
+    (*has_bits)[1] |= 256u;
+  }
+  static void set_has_window_fr(HasBits* has_bits) {
+    (*has_bits)[1] |= 512u;
+  }
+  static void set_has_window_rl(HasBits* has_bits) {
+    (*has_bits)[1] |= 1024u;
+  }
+  static void set_has_window_rr(HasBits* has_bits) {
+    (*has_bits)[1] |= 2048u;
+  }
+  static void set_has_angle_mode(HasBits* has_bits) {
+    (*has_bits)[1] |= 4096u;
+  }
+  static void set_has_angle_active(HasBits* has_bits) {
+    (*has_bits)[1] |= 8192u;
+  }
+  static void set_has_acc_active(HasBits* has_bits) {
+    (*has_bits)[1] |= 16384u;
+  }
+  static void set_has_brake_active(HasBits* has_bits) {
+    (*has_bits)[1] |= 32768u;
+  }
+  static void set_has_brake_type(HasBits* has_bits) {
+    (*has_bits)[1] |= 65536u;
+  }
+  static void set_has_niuju_y(HasBits* has_bits) {
+    (*has_bits)[1] |= 131072u;
+  }
+  static void set_has_auto_mode(HasBits* has_bits) {
+    (*has_bits)[1] |= 262144u;
+  }
+};
+
+decition::decition(::PROTOBUF_NAMESPACE_ID::Arena* arena)
+  : ::PROTOBUF_NAMESPACE_ID::Message(arena) {
+  SharedCtor();
+  RegisterArenaDtor(arena);
+  // @@protoc_insertion_point(arena_constructor:iv.brain.decition)
+}
+decition::decition(const decition& from)
+  : ::PROTOBUF_NAMESPACE_ID::Message(),
+      _has_bits_(from._has_bits_) {
+  _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_);
+  ::memcpy(&speed_, &from.speed_,
+    static_cast<size_t>(reinterpret_cast<char*>(&auto_mode_) -
+    reinterpret_cast<char*>(&speed_)) + sizeof(auto_mode_));
+  // @@protoc_insertion_point(copy_constructor:iv.brain.decition)
+}
+
+void decition::SharedCtor() {
+  ::memset(&speed_, 0, static_cast<size_t>(
+      reinterpret_cast<char*>(&auto_mode_) -
+      reinterpret_cast<char*>(&speed_)) + sizeof(auto_mode_));
+}
+
+decition::~decition() {
+  // @@protoc_insertion_point(destructor:iv.brain.decition)
+  SharedDtor();
+  _internal_metadata_.Delete<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>();
+}
+
+void decition::SharedDtor() {
+  GOOGLE_DCHECK(GetArena() == nullptr);
+}
+
+void decition::ArenaDtor(void* object) {
+  decition* _this = reinterpret_cast< decition* >(object);
+  (void)_this;
+}
+void decition::RegisterArenaDtor(::PROTOBUF_NAMESPACE_ID::Arena*) {
+}
+void decition::SetCachedSize(int size) const {
+  _cached_size_.Set(size);
+}
+const decition& decition::default_instance() {
+  ::PROTOBUF_NAMESPACE_ID::internal::InitSCC(&::scc_info_decition_decition_2eproto.base);
+  return *internal_default_instance();
+}
+
+
+void decition::Clear() {
+// @@protoc_insertion_point(message_clear_start:iv.brain.decition)
+  ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0;
+  // Prevent compiler warnings about cached_has_bits being unused
+  (void) cached_has_bits;
+
+  cached_has_bits = _has_bits_[0];
+  if (cached_has_bits & 0x000000ffu) {
+    ::memset(&speed_, 0, static_cast<size_t>(
+        reinterpret_cast<char*>(&leftlamp_) -
+        reinterpret_cast<char*>(&speed_)) + sizeof(leftlamp_));
+  }
+  if (cached_has_bits & 0x0000ff00u) {
+    ::memset(&rightlamp_, 0, static_cast<size_t>(
+        reinterpret_cast<char*>(&foglamp_) -
+        reinterpret_cast<char*>(&rightlamp_)) + sizeof(foglamp_));
+  }
+  if (cached_has_bits & 0x00ff0000u) {
+    ::memset(&engine_, 0, static_cast<size_t>(
+        reinterpret_cast<char*>(&door_) -
+        reinterpret_cast<char*>(&engine_)) + sizeof(door_));
+  }
+  if (cached_has_bits & 0xff000000u) {
+    ::memset(&gear_, 0, static_cast<size_t>(
+        reinterpret_cast<char*>(&roof_light_) -
+        reinterpret_cast<char*>(&gear_)) + sizeof(roof_light_));
+  }
+  cached_has_bits = _has_bits_[1];
+  if (cached_has_bits & 0x000000ffu) {
+    ::memset(&home_light_, 0, static_cast<size_t>(
+        reinterpret_cast<char*>(&air_off_) -
+        reinterpret_cast<char*>(&home_light_)) + sizeof(air_off_));
+  }
+  if (cached_has_bits & 0x0000ff00u) {
+    ::memset(&window_fl_, 0, static_cast<size_t>(
+        reinterpret_cast<char*>(&brake_active_) -
+        reinterpret_cast<char*>(&window_fl_)) + sizeof(brake_active_));
+  }
+  if (cached_has_bits & 0x00070000u) {
+    ::memset(&brake_type_, 0, static_cast<size_t>(
+        reinterpret_cast<char*>(&auto_mode_) -
+        reinterpret_cast<char*>(&brake_type_)) + sizeof(auto_mode_));
+  }
+  _has_bits_.Clear();
+  _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>();
+}
+
+const char* decition::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID::internal::ParseContext* ctx) {
+#define CHK_(x) if (PROTOBUF_PREDICT_FALSE(!(x))) goto failure
+  ::PROTOBUF_NAMESPACE_ID::Arena* arena = GetArena(); (void)arena;
+  while (!ctx->Done(&ptr)) {
+    ::PROTOBUF_NAMESPACE_ID::uint32 tag;
+    ptr = ::PROTOBUF_NAMESPACE_ID::internal::ReadTag(ptr, &tag);
+    CHK_(ptr);
+    switch (tag >> 3) {
+      // optional float speed = 1;
+      case 1:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 13)) {
+          _Internal::set_has_speed(&_has_bits_);
+          speed_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad<float>(ptr);
+          ptr += sizeof(float);
+        } else goto handle_unusual;
+        continue;
+      // optional float wheelAngle = 2;
+      case 2:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 21)) {
+          _Internal::set_has_wheelangle(&_has_bits_);
+          wheelangle_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad<float>(ptr);
+          ptr += sizeof(float);
+        } else goto handle_unusual;
+        continue;
+      // optional float wheelSpeed = 3;
+      case 3:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 29)) {
+          _Internal::set_has_wheelspeed(&_has_bits_);
+          wheelspeed_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad<float>(ptr);
+          ptr += sizeof(float);
+        } else goto handle_unusual;
+        continue;
+      // optional float lateralTorque = 4;
+      case 4:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 37)) {
+          _Internal::set_has_lateraltorque(&_has_bits_);
+          lateraltorque_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad<float>(ptr);
+          ptr += sizeof(float);
+        } else goto handle_unusual;
+        continue;
+      // optional float brake = 5;
+      case 5:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 45)) {
+          _Internal::set_has_brake(&_has_bits_);
+          brake_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad<float>(ptr);
+          ptr += sizeof(float);
+        } else goto handle_unusual;
+        continue;
+      // optional float accelerator = 6;
+      case 6:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 53)) {
+          _Internal::set_has_accelerator(&_has_bits_);
+          accelerator_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad<float>(ptr);
+          ptr += sizeof(float);
+        } else goto handle_unusual;
+        continue;
+      // optional float torque = 7;
+      case 7:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 61)) {
+          _Internal::set_has_torque(&_has_bits_);
+          torque_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad<float>(ptr);
+          ptr += sizeof(float);
+        } else goto handle_unusual;
+        continue;
+      // optional bool leftLamp = 8;
+      case 8:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 64)) {
+          _Internal::set_has_leftlamp(&_has_bits_);
+          leftlamp_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional bool rightLamp = 9;
+      case 9:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 72)) {
+          _Internal::set_has_rightlamp(&_has_bits_);
+          rightlamp_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional bool doubleSpark = 10;
+      case 10:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 80)) {
+          _Internal::set_has_doublespark(&_has_bits_);
+          doublespark_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional bool headLight = 11;
+      case 11:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 88)) {
+          _Internal::set_has_headlight(&_has_bits_);
+          headlight_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional bool highBeam = 12;
+      case 12:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 96)) {
+          _Internal::set_has_highbeam(&_has_bits_);
+          highbeam_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional int32 dippedLight = 13;
+      case 13:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 104)) {
+          _Internal::set_has_dippedlight(&_has_bits_);
+          dippedlight_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional bool tailLight = 14;
+      case 14:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 112)) {
+          _Internal::set_has_taillight(&_has_bits_);
+          taillight_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional bool domeLight = 15;
+      case 15:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 120)) {
+          _Internal::set_has_domelight(&_has_bits_);
+          domelight_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional bool fogLamp = 16;
+      case 16:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 128)) {
+          _Internal::set_has_foglamp(&_has_bits_);
+          foglamp_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional bool backupLight = 17;
+      case 17:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 136)) {
+          _Internal::set_has_backuplight(&_has_bits_);
+          backuplight_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional bool brakeLamp = 18;
+      case 18:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 144)) {
+          _Internal::set_has_brakelamp(&_has_bits_);
+          brakelamp_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional int32 engine = 19;
+      case 19:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 152)) {
+          _Internal::set_has_engine(&_has_bits_);
+          engine_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional int32 mode = 20;
+      case 20:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 160)) {
+          _Internal::set_has_mode(&_has_bits_);
+          mode_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional int32 handBrake = 21;
+      case 21:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 168)) {
+          _Internal::set_has_handbrake(&_has_bits_);
+          handbrake_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional bool speak = 22;
+      case 22:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 176)) {
+          _Internal::set_has_speak(&_has_bits_);
+          speak_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional int32 door = 23;
+      case 23:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 184)) {
+          _Internal::set_has_door(&_has_bits_);
+          door_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional int32 gear = 24;
+      case 24:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 192)) {
+          _Internal::set_has_gear(&_has_bits_);
+          gear_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional int32 wiper = 25;
+      case 25:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 200)) {
+          _Internal::set_has_wiper(&_has_bits_);
+          wiper_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional int32 grade = 26;
+      case 26:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 208)) {
+          _Internal::set_has_grade(&_has_bits_);
+          grade_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional float ttc = 27;
+      case 27:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 221)) {
+          _Internal::set_has_ttc(&_has_bits_);
+          ttc_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad<float>(ptr);
+          ptr += sizeof(float);
+        } else goto handle_unusual;
+        continue;
+      // optional bool air_enable = 28;
+      case 28:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 224)) {
+          _Internal::set_has_air_enable(&_has_bits_);
+          air_enable_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional float air_temp = 29;
+      case 29:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 237)) {
+          _Internal::set_has_air_temp(&_has_bits_);
+          air_temp_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad<float>(ptr);
+          ptr += sizeof(float);
+        } else goto handle_unusual;
+        continue;
+      // optional float air_mode = 30;
+      case 30:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 245)) {
+          _Internal::set_has_air_mode(&_has_bits_);
+          air_mode_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad<float>(ptr);
+          ptr += sizeof(float);
+        } else goto handle_unusual;
+        continue;
+      // optional float wind_level = 31;
+      case 31:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 253)) {
+          _Internal::set_has_wind_level(&_has_bits_);
+          wind_level_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad<float>(ptr);
+          ptr += sizeof(float);
+        } else goto handle_unusual;
+        continue;
+      // optional int32 roof_light = 32;
+      case 32:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 0)) {
+          _Internal::set_has_roof_light(&_has_bits_);
+          roof_light_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional int32 home_light = 33;
+      case 33:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 8)) {
+          _Internal::set_has_home_light(&_has_bits_);
+          home_light_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional float air_worktime = 34;
+      case 34:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 21)) {
+          _Internal::set_has_air_worktime(&_has_bits_);
+          air_worktime_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad<float>(ptr);
+          ptr += sizeof(float);
+        } else goto handle_unusual;
+        continue;
+      // optional float air_offtime = 35;
+      case 35:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 29)) {
+          _Internal::set_has_air_offtime(&_has_bits_);
+          air_offtime_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad<float>(ptr);
+          ptr += sizeof(float);
+        } else goto handle_unusual;
+        continue;
+      // optional bool air_on = 36;
+      case 36:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 32)) {
+          _Internal::set_has_air_on(&_has_bits_);
+          air_on_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional bool air_ac = 37;
+      case 37:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 40)) {
+          _Internal::set_has_air_ac(&_has_bits_);
+          air_ac_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional bool air_circle = 38;
+      case 38:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 48)) {
+          _Internal::set_has_air_circle(&_has_bits_);
+          air_circle_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional bool air_auto = 39;
+      case 39:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 56)) {
+          _Internal::set_has_air_auto(&_has_bits_);
+          air_auto_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional bool air_off = 40;
+      case 40:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 64)) {
+          _Internal::set_has_air_off(&_has_bits_);
+          air_off_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional uint32 window_fl = 41;
+      case 41:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 72)) {
+          _Internal::set_has_window_fl(&_has_bits_);
+          window_fl_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional uint32 window_fr = 42;
+      case 42:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 80)) {
+          _Internal::set_has_window_fr(&_has_bits_);
+          window_fr_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional uint32 window_rl = 43;
+      case 43:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 88)) {
+          _Internal::set_has_window_rl(&_has_bits_);
+          window_rl_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional uint32 window_rr = 44;
+      case 44:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 96)) {
+          _Internal::set_has_window_rr(&_has_bits_);
+          window_rr_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional uint32 angle_mode = 45;
+      case 45:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 104)) {
+          _Internal::set_has_angle_mode(&_has_bits_);
+          angle_mode_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional uint32 angle_active = 46;
+      case 46:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 112)) {
+          _Internal::set_has_angle_active(&_has_bits_);
+          angle_active_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional uint32 acc_active = 47;
+      case 47:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 120)) {
+          _Internal::set_has_acc_active(&_has_bits_);
+          acc_active_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional uint32 brake_active = 48;
+      case 48:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 128)) {
+          _Internal::set_has_brake_active(&_has_bits_);
+          brake_active_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional uint32 brake_type = 49;
+      case 49:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 136)) {
+          _Internal::set_has_brake_type(&_has_bits_);
+          brake_type_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      // optional float niuju_y = 50;
+      case 50:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 149)) {
+          _Internal::set_has_niuju_y(&_has_bits_);
+          niuju_y_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad<float>(ptr);
+          ptr += sizeof(float);
+        } else goto handle_unusual;
+        continue;
+      // optional uint32 auto_mode = 51;
+      case 51:
+        if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 152)) {
+          _Internal::set_has_auto_mode(&_has_bits_);
+          auto_mode_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr);
+          CHK_(ptr);
+        } else goto handle_unusual;
+        continue;
+      default: {
+      handle_unusual:
+        if ((tag & 7) == 4 || tag == 0) {
+          ctx->SetLastTag(tag);
+          goto success;
+        }
+        ptr = UnknownFieldParse(tag,
+            _internal_metadata_.mutable_unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(),
+            ptr, ctx);
+        CHK_(ptr != nullptr);
+        continue;
+      }
+    }  // switch
+  }  // while
+success:
+  return ptr;
+failure:
+  ptr = nullptr;
+  goto success;
+#undef CHK_
+}
+
+::PROTOBUF_NAMESPACE_ID::uint8* decition::_InternalSerialize(
+    ::PROTOBUF_NAMESPACE_ID::uint8* target, ::PROTOBUF_NAMESPACE_ID::io::EpsCopyOutputStream* stream) const {
+  // @@protoc_insertion_point(serialize_to_array_start:iv.brain.decition)
+  ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0;
+  (void) cached_has_bits;
+
+  cached_has_bits = _has_bits_[0];
+  // optional float speed = 1;
+  if (cached_has_bits & 0x00000001u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(1, this->_internal_speed(), target);
+  }
+
+  // optional float wheelAngle = 2;
+  if (cached_has_bits & 0x00000002u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(2, this->_internal_wheelangle(), target);
+  }
+
+  // optional float wheelSpeed = 3;
+  if (cached_has_bits & 0x00000004u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(3, this->_internal_wheelspeed(), target);
+  }
+
+  // optional float lateralTorque = 4;
+  if (cached_has_bits & 0x00000008u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(4, this->_internal_lateraltorque(), target);
+  }
+
+  // optional float brake = 5;
+  if (cached_has_bits & 0x00000010u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(5, this->_internal_brake(), target);
+  }
+
+  // optional float accelerator = 6;
+  if (cached_has_bits & 0x00000020u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(6, this->_internal_accelerator(), target);
+  }
+
+  // optional float torque = 7;
+  if (cached_has_bits & 0x00000040u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(7, this->_internal_torque(), target);
+  }
+
+  // optional bool leftLamp = 8;
+  if (cached_has_bits & 0x00000080u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteBoolToArray(8, this->_internal_leftlamp(), target);
+  }
+
+  // optional bool rightLamp = 9;
+  if (cached_has_bits & 0x00000100u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteBoolToArray(9, this->_internal_rightlamp(), target);
+  }
+
+  // optional bool doubleSpark = 10;
+  if (cached_has_bits & 0x00000200u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteBoolToArray(10, this->_internal_doublespark(), target);
+  }
+
+  // optional bool headLight = 11;
+  if (cached_has_bits & 0x00000400u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteBoolToArray(11, this->_internal_headlight(), target);
+  }
+
+  // optional bool highBeam = 12;
+  if (cached_has_bits & 0x00001000u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteBoolToArray(12, this->_internal_highbeam(), target);
+  }
+
+  // optional int32 dippedLight = 13;
+  if (cached_has_bits & 0x00000800u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteInt32ToArray(13, this->_internal_dippedlight(), target);
+  }
+
+  // optional bool tailLight = 14;
+  if (cached_has_bits & 0x00002000u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteBoolToArray(14, this->_internal_taillight(), target);
+  }
+
+  // optional bool domeLight = 15;
+  if (cached_has_bits & 0x00004000u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteBoolToArray(15, this->_internal_domelight(), target);
+  }
+
+  // optional bool fogLamp = 16;
+  if (cached_has_bits & 0x00008000u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteBoolToArray(16, this->_internal_foglamp(), target);
+  }
+
+  // optional bool backupLight = 17;
+  if (cached_has_bits & 0x00080000u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteBoolToArray(17, this->_internal_backuplight(), target);
+  }
+
+  // optional bool brakeLamp = 18;
+  if (cached_has_bits & 0x00100000u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteBoolToArray(18, this->_internal_brakelamp(), target);
+  }
+
+  // optional int32 engine = 19;
+  if (cached_has_bits & 0x00010000u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteInt32ToArray(19, this->_internal_engine(), target);
+  }
+
+  // optional int32 mode = 20;
+  if (cached_has_bits & 0x00020000u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteInt32ToArray(20, this->_internal_mode(), target);
+  }
+
+  // optional int32 handBrake = 21;
+  if (cached_has_bits & 0x00040000u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteInt32ToArray(21, this->_internal_handbrake(), target);
+  }
+
+  // optional bool speak = 22;
+  if (cached_has_bits & 0x00200000u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteBoolToArray(22, this->_internal_speak(), target);
+  }
+
+  // optional int32 door = 23;
+  if (cached_has_bits & 0x00800000u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteInt32ToArray(23, this->_internal_door(), target);
+  }
+
+  // optional int32 gear = 24;
+  if (cached_has_bits & 0x01000000u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteInt32ToArray(24, this->_internal_gear(), target);
+  }
+
+  // optional int32 wiper = 25;
+  if (cached_has_bits & 0x02000000u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteInt32ToArray(25, this->_internal_wiper(), target);
+  }
+
+  // optional int32 grade = 26;
+  if (cached_has_bits & 0x04000000u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteInt32ToArray(26, this->_internal_grade(), target);
+  }
+
+  // optional float ttc = 27;
+  if (cached_has_bits & 0x08000000u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(27, this->_internal_ttc(), target);
+  }
+
+  // optional bool air_enable = 28;
+  if (cached_has_bits & 0x00400000u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteBoolToArray(28, this->_internal_air_enable(), target);
+  }
+
+  // optional float air_temp = 29;
+  if (cached_has_bits & 0x10000000u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(29, this->_internal_air_temp(), target);
+  }
+
+  // optional float air_mode = 30;
+  if (cached_has_bits & 0x20000000u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(30, this->_internal_air_mode(), target);
+  }
+
+  // optional float wind_level = 31;
+  if (cached_has_bits & 0x40000000u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(31, this->_internal_wind_level(), target);
+  }
+
+  // optional int32 roof_light = 32;
+  if (cached_has_bits & 0x80000000u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteInt32ToArray(32, this->_internal_roof_light(), target);
+  }
+
+  cached_has_bits = _has_bits_[1];
+  // optional int32 home_light = 33;
+  if (cached_has_bits & 0x00000001u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteInt32ToArray(33, this->_internal_home_light(), target);
+  }
+
+  // optional float air_worktime = 34;
+  if (cached_has_bits & 0x00000002u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(34, this->_internal_air_worktime(), target);
+  }
+
+  // optional float air_offtime = 35;
+  if (cached_has_bits & 0x00000004u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(35, this->_internal_air_offtime(), target);
+  }
+
+  // optional bool air_on = 36;
+  if (cached_has_bits & 0x00000008u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteBoolToArray(36, this->_internal_air_on(), target);
+  }
+
+  // optional bool air_ac = 37;
+  if (cached_has_bits & 0x00000010u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteBoolToArray(37, this->_internal_air_ac(), target);
+  }
+
+  // optional bool air_circle = 38;
+  if (cached_has_bits & 0x00000020u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteBoolToArray(38, this->_internal_air_circle(), target);
+  }
+
+  // optional bool air_auto = 39;
+  if (cached_has_bits & 0x00000040u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteBoolToArray(39, this->_internal_air_auto(), target);
+  }
+
+  // optional bool air_off = 40;
+  if (cached_has_bits & 0x00000080u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteBoolToArray(40, this->_internal_air_off(), target);
+  }
+
+  // optional uint32 window_fl = 41;
+  if (cached_has_bits & 0x00000100u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteUInt32ToArray(41, this->_internal_window_fl(), target);
+  }
+
+  // optional uint32 window_fr = 42;
+  if (cached_has_bits & 0x00000200u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteUInt32ToArray(42, this->_internal_window_fr(), target);
+  }
+
+  // optional uint32 window_rl = 43;
+  if (cached_has_bits & 0x00000400u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteUInt32ToArray(43, this->_internal_window_rl(), target);
+  }
+
+  // optional uint32 window_rr = 44;
+  if (cached_has_bits & 0x00000800u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteUInt32ToArray(44, this->_internal_window_rr(), target);
+  }
+
+  // optional uint32 angle_mode = 45;
+  if (cached_has_bits & 0x00001000u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteUInt32ToArray(45, this->_internal_angle_mode(), target);
+  }
+
+  // optional uint32 angle_active = 46;
+  if (cached_has_bits & 0x00002000u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteUInt32ToArray(46, this->_internal_angle_active(), target);
+  }
+
+  // optional uint32 acc_active = 47;
+  if (cached_has_bits & 0x00004000u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteUInt32ToArray(47, this->_internal_acc_active(), target);
+  }
+
+  // optional uint32 brake_active = 48;
+  if (cached_has_bits & 0x00008000u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteUInt32ToArray(48, this->_internal_brake_active(), target);
+  }
+
+  // optional uint32 brake_type = 49;
+  if (cached_has_bits & 0x00010000u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteUInt32ToArray(49, this->_internal_brake_type(), target);
+  }
+
+  // optional float niuju_y = 50;
+  if (cached_has_bits & 0x00020000u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(50, this->_internal_niuju_y(), target);
+  }
+
+  // optional uint32 auto_mode = 51;
+  if (cached_has_bits & 0x00040000u) {
+    target = stream->EnsureSpace(target);
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteUInt32ToArray(51, this->_internal_auto_mode(), target);
+  }
+
+  if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) {
+    target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormat::InternalSerializeUnknownFieldsToArray(
+        _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream);
+  }
+  // @@protoc_insertion_point(serialize_to_array_end:iv.brain.decition)
+  return target;
+}
+
+size_t decition::ByteSizeLong() const {
+// @@protoc_insertion_point(message_byte_size_start:iv.brain.decition)
+  size_t total_size = 0;
+
+  ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0;
+  // Prevent compiler warnings about cached_has_bits being unused
+  (void) cached_has_bits;
+
+  cached_has_bits = _has_bits_[0];
+  if (cached_has_bits & 0x000000ffu) {
+    // optional float speed = 1;
+    if (cached_has_bits & 0x00000001u) {
+      total_size += 1 + 4;
+    }
+
+    // optional float wheelAngle = 2;
+    if (cached_has_bits & 0x00000002u) {
+      total_size += 1 + 4;
+    }
+
+    // optional float wheelSpeed = 3;
+    if (cached_has_bits & 0x00000004u) {
+      total_size += 1 + 4;
+    }
+
+    // optional float lateralTorque = 4;
+    if (cached_has_bits & 0x00000008u) {
+      total_size += 1 + 4;
+    }
+
+    // optional float brake = 5;
+    if (cached_has_bits & 0x00000010u) {
+      total_size += 1 + 4;
+    }
+
+    // optional float accelerator = 6;
+    if (cached_has_bits & 0x00000020u) {
+      total_size += 1 + 4;
+    }
+
+    // optional float torque = 7;
+    if (cached_has_bits & 0x00000040u) {
+      total_size += 1 + 4;
+    }
+
+    // optional bool leftLamp = 8;
+    if (cached_has_bits & 0x00000080u) {
+      total_size += 1 + 1;
+    }
+
+  }
+  if (cached_has_bits & 0x0000ff00u) {
+    // optional bool rightLamp = 9;
+    if (cached_has_bits & 0x00000100u) {
+      total_size += 1 + 1;
+    }
+
+    // optional bool doubleSpark = 10;
+    if (cached_has_bits & 0x00000200u) {
+      total_size += 1 + 1;
+    }
+
+    // optional bool headLight = 11;
+    if (cached_has_bits & 0x00000400u) {
+      total_size += 1 + 1;
+    }
+
+    // optional int32 dippedLight = 13;
+    if (cached_has_bits & 0x00000800u) {
+      total_size += 1 +
+        ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::Int32Size(
+          this->_internal_dippedlight());
+    }
+
+    // optional bool highBeam = 12;
+    if (cached_has_bits & 0x00001000u) {
+      total_size += 1 + 1;
+    }
+
+    // optional bool tailLight = 14;
+    if (cached_has_bits & 0x00002000u) {
+      total_size += 1 + 1;
+    }
+
+    // optional bool domeLight = 15;
+    if (cached_has_bits & 0x00004000u) {
+      total_size += 1 + 1;
+    }
+
+    // optional bool fogLamp = 16;
+    if (cached_has_bits & 0x00008000u) {
+      total_size += 2 + 1;
+    }
+
+  }
+  if (cached_has_bits & 0x00ff0000u) {
+    // optional int32 engine = 19;
+    if (cached_has_bits & 0x00010000u) {
+      total_size += 2 +
+        ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::Int32Size(
+          this->_internal_engine());
+    }
+
+    // optional int32 mode = 20;
+    if (cached_has_bits & 0x00020000u) {
+      total_size += 2 +
+        ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::Int32Size(
+          this->_internal_mode());
+    }
+
+    // optional int32 handBrake = 21;
+    if (cached_has_bits & 0x00040000u) {
+      total_size += 2 +
+        ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::Int32Size(
+          this->_internal_handbrake());
+    }
+
+    // optional bool backupLight = 17;
+    if (cached_has_bits & 0x00080000u) {
+      total_size += 2 + 1;
+    }
+
+    // optional bool brakeLamp = 18;
+    if (cached_has_bits & 0x00100000u) {
+      total_size += 2 + 1;
+    }
+
+    // optional bool speak = 22;
+    if (cached_has_bits & 0x00200000u) {
+      total_size += 2 + 1;
+    }
+
+    // optional bool air_enable = 28;
+    if (cached_has_bits & 0x00400000u) {
+      total_size += 2 + 1;
+    }
+
+    // optional int32 door = 23;
+    if (cached_has_bits & 0x00800000u) {
+      total_size += 2 +
+        ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::Int32Size(
+          this->_internal_door());
+    }
+
+  }
+  if (cached_has_bits & 0xff000000u) {
+    // optional int32 gear = 24;
+    if (cached_has_bits & 0x01000000u) {
+      total_size += 2 +
+        ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::Int32Size(
+          this->_internal_gear());
+    }
+
+    // optional int32 wiper = 25;
+    if (cached_has_bits & 0x02000000u) {
+      total_size += 2 +
+        ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::Int32Size(
+          this->_internal_wiper());
+    }
+
+    // optional int32 grade = 26;
+    if (cached_has_bits & 0x04000000u) {
+      total_size += 2 +
+        ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::Int32Size(
+          this->_internal_grade());
+    }
+
+    // optional float ttc = 27;
+    if (cached_has_bits & 0x08000000u) {
+      total_size += 2 + 4;
+    }
+
+    // optional float air_temp = 29;
+    if (cached_has_bits & 0x10000000u) {
+      total_size += 2 + 4;
+    }
+
+    // optional float air_mode = 30;
+    if (cached_has_bits & 0x20000000u) {
+      total_size += 2 + 4;
+    }
+
+    // optional float wind_level = 31;
+    if (cached_has_bits & 0x40000000u) {
+      total_size += 2 + 4;
+    }
+
+    // optional int32 roof_light = 32;
+    if (cached_has_bits & 0x80000000u) {
+      total_size += 2 +
+        ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::Int32Size(
+          this->_internal_roof_light());
+    }
+
+  }
+  cached_has_bits = _has_bits_[1];
+  if (cached_has_bits & 0x000000ffu) {
+    // optional int32 home_light = 33;
+    if (cached_has_bits & 0x00000001u) {
+      total_size += 2 +
+        ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::Int32Size(
+          this->_internal_home_light());
+    }
+
+    // optional float air_worktime = 34;
+    if (cached_has_bits & 0x00000002u) {
+      total_size += 2 + 4;
+    }
+
+    // optional float air_offtime = 35;
+    if (cached_has_bits & 0x00000004u) {
+      total_size += 2 + 4;
+    }
+
+    // optional bool air_on = 36;
+    if (cached_has_bits & 0x00000008u) {
+      total_size += 2 + 1;
+    }
+
+    // optional bool air_ac = 37;
+    if (cached_has_bits & 0x00000010u) {
+      total_size += 2 + 1;
+    }
+
+    // optional bool air_circle = 38;
+    if (cached_has_bits & 0x00000020u) {
+      total_size += 2 + 1;
+    }
+
+    // optional bool air_auto = 39;
+    if (cached_has_bits & 0x00000040u) {
+      total_size += 2 + 1;
+    }
+
+    // optional bool air_off = 40;
+    if (cached_has_bits & 0x00000080u) {
+      total_size += 2 + 1;
+    }
+
+  }
+  if (cached_has_bits & 0x0000ff00u) {
+    // optional uint32 window_fl = 41;
+    if (cached_has_bits & 0x00000100u) {
+      total_size += 2 +
+        ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::UInt32Size(
+          this->_internal_window_fl());
+    }
+
+    // optional uint32 window_fr = 42;
+    if (cached_has_bits & 0x00000200u) {
+      total_size += 2 +
+        ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::UInt32Size(
+          this->_internal_window_fr());
+    }
+
+    // optional uint32 window_rl = 43;
+    if (cached_has_bits & 0x00000400u) {
+      total_size += 2 +
+        ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::UInt32Size(
+          this->_internal_window_rl());
+    }
+
+    // optional uint32 window_rr = 44;
+    if (cached_has_bits & 0x00000800u) {
+      total_size += 2 +
+        ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::UInt32Size(
+          this->_internal_window_rr());
+    }
+
+    // optional uint32 angle_mode = 45;
+    if (cached_has_bits & 0x00001000u) {
+      total_size += 2 +
+        ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::UInt32Size(
+          this->_internal_angle_mode());
+    }
+
+    // optional uint32 angle_active = 46;
+    if (cached_has_bits & 0x00002000u) {
+      total_size += 2 +
+        ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::UInt32Size(
+          this->_internal_angle_active());
+    }
+
+    // optional uint32 acc_active = 47;
+    if (cached_has_bits & 0x00004000u) {
+      total_size += 2 +
+        ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::UInt32Size(
+          this->_internal_acc_active());
+    }
+
+    // optional uint32 brake_active = 48;
+    if (cached_has_bits & 0x00008000u) {
+      total_size += 2 +
+        ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::UInt32Size(
+          this->_internal_brake_active());
+    }
+
+  }
+  if (cached_has_bits & 0x00070000u) {
+    // optional uint32 brake_type = 49;
+    if (cached_has_bits & 0x00010000u) {
+      total_size += 2 +
+        ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::UInt32Size(
+          this->_internal_brake_type());
+    }
+
+    // optional float niuju_y = 50;
+    if (cached_has_bits & 0x00020000u) {
+      total_size += 2 + 4;
+    }
+
+    // optional uint32 auto_mode = 51;
+    if (cached_has_bits & 0x00040000u) {
+      total_size += 2 +
+        ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::UInt32Size(
+          this->_internal_auto_mode());
+    }
+
+  }
+  if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) {
+    return ::PROTOBUF_NAMESPACE_ID::internal::ComputeUnknownFieldsSize(
+        _internal_metadata_, total_size, &_cached_size_);
+  }
+  int cached_size = ::PROTOBUF_NAMESPACE_ID::internal::ToCachedSize(total_size);
+  SetCachedSize(cached_size);
+  return total_size;
+}
+
+void decition::MergeFrom(const ::PROTOBUF_NAMESPACE_ID::Message& from) {
+// @@protoc_insertion_point(generalized_merge_from_start:iv.brain.decition)
+  GOOGLE_DCHECK_NE(&from, this);
+  const decition* source =
+      ::PROTOBUF_NAMESPACE_ID::DynamicCastToGenerated<decition>(
+          &from);
+  if (source == nullptr) {
+  // @@protoc_insertion_point(generalized_merge_from_cast_fail:iv.brain.decition)
+    ::PROTOBUF_NAMESPACE_ID::internal::ReflectionOps::Merge(from, this);
+  } else {
+  // @@protoc_insertion_point(generalized_merge_from_cast_success:iv.brain.decition)
+    MergeFrom(*source);
+  }
+}
+
+void decition::MergeFrom(const decition& from) {
+// @@protoc_insertion_point(class_specific_merge_from_start:iv.brain.decition)
+  GOOGLE_DCHECK_NE(&from, this);
+  _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_);
+  ::PROTOBUF_NAMESPACE_ID::uint32 cached_has_bits = 0;
+  (void) cached_has_bits;
+
+  cached_has_bits = from._has_bits_[0];
+  if (cached_has_bits & 0x000000ffu) {
+    if (cached_has_bits & 0x00000001u) {
+      speed_ = from.speed_;
+    }
+    if (cached_has_bits & 0x00000002u) {
+      wheelangle_ = from.wheelangle_;
+    }
+    if (cached_has_bits & 0x00000004u) {
+      wheelspeed_ = from.wheelspeed_;
+    }
+    if (cached_has_bits & 0x00000008u) {
+      lateraltorque_ = from.lateraltorque_;
+    }
+    if (cached_has_bits & 0x00000010u) {
+      brake_ = from.brake_;
+    }
+    if (cached_has_bits & 0x00000020u) {
+      accelerator_ = from.accelerator_;
+    }
+    if (cached_has_bits & 0x00000040u) {
+      torque_ = from.torque_;
+    }
+    if (cached_has_bits & 0x00000080u) {
+      leftlamp_ = from.leftlamp_;
+    }
+    _has_bits_[0] |= cached_has_bits;
+  }
+  if (cached_has_bits & 0x0000ff00u) {
+    if (cached_has_bits & 0x00000100u) {
+      rightlamp_ = from.rightlamp_;
+    }
+    if (cached_has_bits & 0x00000200u) {
+      doublespark_ = from.doublespark_;
+    }
+    if (cached_has_bits & 0x00000400u) {
+      headlight_ = from.headlight_;
+    }
+    if (cached_has_bits & 0x00000800u) {
+      dippedlight_ = from.dippedlight_;
+    }
+    if (cached_has_bits & 0x00001000u) {
+      highbeam_ = from.highbeam_;
+    }
+    if (cached_has_bits & 0x00002000u) {
+      taillight_ = from.taillight_;
+    }
+    if (cached_has_bits & 0x00004000u) {
+      domelight_ = from.domelight_;
+    }
+    if (cached_has_bits & 0x00008000u) {
+      foglamp_ = from.foglamp_;
+    }
+    _has_bits_[0] |= cached_has_bits;
+  }
+  if (cached_has_bits & 0x00ff0000u) {
+    if (cached_has_bits & 0x00010000u) {
+      engine_ = from.engine_;
+    }
+    if (cached_has_bits & 0x00020000u) {
+      mode_ = from.mode_;
+    }
+    if (cached_has_bits & 0x00040000u) {
+      handbrake_ = from.handbrake_;
+    }
+    if (cached_has_bits & 0x00080000u) {
+      backuplight_ = from.backuplight_;
+    }
+    if (cached_has_bits & 0x00100000u) {
+      brakelamp_ = from.brakelamp_;
+    }
+    if (cached_has_bits & 0x00200000u) {
+      speak_ = from.speak_;
+    }
+    if (cached_has_bits & 0x00400000u) {
+      air_enable_ = from.air_enable_;
+    }
+    if (cached_has_bits & 0x00800000u) {
+      door_ = from.door_;
+    }
+    _has_bits_[0] |= cached_has_bits;
+  }
+  if (cached_has_bits & 0xff000000u) {
+    if (cached_has_bits & 0x01000000u) {
+      gear_ = from.gear_;
+    }
+    if (cached_has_bits & 0x02000000u) {
+      wiper_ = from.wiper_;
+    }
+    if (cached_has_bits & 0x04000000u) {
+      grade_ = from.grade_;
+    }
+    if (cached_has_bits & 0x08000000u) {
+      ttc_ = from.ttc_;
+    }
+    if (cached_has_bits & 0x10000000u) {
+      air_temp_ = from.air_temp_;
+    }
+    if (cached_has_bits & 0x20000000u) {
+      air_mode_ = from.air_mode_;
+    }
+    if (cached_has_bits & 0x40000000u) {
+      wind_level_ = from.wind_level_;
+    }
+    if (cached_has_bits & 0x80000000u) {
+      roof_light_ = from.roof_light_;
+    }
+    _has_bits_[0] |= cached_has_bits;
+  }
+  cached_has_bits = from._has_bits_[1];
+  if (cached_has_bits & 0x000000ffu) {
+    if (cached_has_bits & 0x00000001u) {
+      home_light_ = from.home_light_;
+    }
+    if (cached_has_bits & 0x00000002u) {
+      air_worktime_ = from.air_worktime_;
+    }
+    if (cached_has_bits & 0x00000004u) {
+      air_offtime_ = from.air_offtime_;
+    }
+    if (cached_has_bits & 0x00000008u) {
+      air_on_ = from.air_on_;
+    }
+    if (cached_has_bits & 0x00000010u) {
+      air_ac_ = from.air_ac_;
+    }
+    if (cached_has_bits & 0x00000020u) {
+      air_circle_ = from.air_circle_;
+    }
+    if (cached_has_bits & 0x00000040u) {
+      air_auto_ = from.air_auto_;
+    }
+    if (cached_has_bits & 0x00000080u) {
+      air_off_ = from.air_off_;
+    }
+    _has_bits_[1] |= cached_has_bits;
+  }
+  if (cached_has_bits & 0x0000ff00u) {
+    if (cached_has_bits & 0x00000100u) {
+      window_fl_ = from.window_fl_;
+    }
+    if (cached_has_bits & 0x00000200u) {
+      window_fr_ = from.window_fr_;
+    }
+    if (cached_has_bits & 0x00000400u) {
+      window_rl_ = from.window_rl_;
+    }
+    if (cached_has_bits & 0x00000800u) {
+      window_rr_ = from.window_rr_;
+    }
+    if (cached_has_bits & 0x00001000u) {
+      angle_mode_ = from.angle_mode_;
+    }
+    if (cached_has_bits & 0x00002000u) {
+      angle_active_ = from.angle_active_;
+    }
+    if (cached_has_bits & 0x00004000u) {
+      acc_active_ = from.acc_active_;
+    }
+    if (cached_has_bits & 0x00008000u) {
+      brake_active_ = from.brake_active_;
+    }
+    _has_bits_[1] |= cached_has_bits;
+  }
+  if (cached_has_bits & 0x00070000u) {
+    if (cached_has_bits & 0x00010000u) {
+      brake_type_ = from.brake_type_;
+    }
+    if (cached_has_bits & 0x00020000u) {
+      niuju_y_ = from.niuju_y_;
+    }
+    if (cached_has_bits & 0x00040000u) {
+      auto_mode_ = from.auto_mode_;
+    }
+    _has_bits_[1] |= cached_has_bits;
+  }
+}
+
+void decition::CopyFrom(const ::PROTOBUF_NAMESPACE_ID::Message& from) {
+// @@protoc_insertion_point(generalized_copy_from_start:iv.brain.decition)
+  if (&from == this) return;
+  Clear();
+  MergeFrom(from);
+}
+
+void decition::CopyFrom(const decition& from) {
+// @@protoc_insertion_point(class_specific_copy_from_start:iv.brain.decition)
+  if (&from == this) return;
+  Clear();
+  MergeFrom(from);
+}
+
+bool decition::IsInitialized() const {
+  return true;
+}
+
+void decition::InternalSwap(decition* other) {
+  using std::swap;
+  _internal_metadata_.Swap<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(&other->_internal_metadata_);
+  swap(_has_bits_[0], other->_has_bits_[0]);
+  swap(_has_bits_[1], other->_has_bits_[1]);
+  ::PROTOBUF_NAMESPACE_ID::internal::memswap<
+      PROTOBUF_FIELD_OFFSET(decition, auto_mode_)
+      + sizeof(decition::auto_mode_)
+      - PROTOBUF_FIELD_OFFSET(decition, speed_)>(
+          reinterpret_cast<char*>(&speed_),
+          reinterpret_cast<char*>(&other->speed_));
+}
+
+::PROTOBUF_NAMESPACE_ID::Metadata decition::GetMetadata() const {
+  return GetMetadataStatic();
+}
+
+
+// @@protoc_insertion_point(namespace_scope)
+}  // namespace brain
+}  // namespace iv
+PROTOBUF_NAMESPACE_OPEN
+template<> PROTOBUF_NOINLINE ::iv::brain::decition* Arena::CreateMaybeMessage< ::iv::brain::decition >(Arena* arena) {
+  return Arena::CreateMessageInternal< ::iv::brain::decition >(arena);
+}
+PROTOBUF_NAMESPACE_CLOSE
+
+// @@protoc_insertion_point(global_scope)
+#include <google/protobuf/port_undef.inc>