00001 /* 00002 * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA) 00003 * 00004 * Licensed under the Apache License, Version 2.0 (the "License"); 00005 * you may not use this file except in compliance with the License. 00006 * You may obtain a copy of the License at 00007 * 00008 * http://www.apache.org/licenses/LICENSE-2.0 00009 00010 * Unless required by applicable law or agreed to in writing, software 00011 * distributed under the License is distributed on an "AS IS" BASIS, 00012 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 00013 * See the License for the specific language governing permissions and 00014 * limitations under the License. 00015 */ 00016 00017 00018 #ifndef COB_BMS_DRIVER_NODE_H 00019 #define COB_BMS_DRIVER_NODE_H 00020 00021 #include <ros/ros.h> 00022 #include <XmlRpcValue.h> 00023 #include <diagnostic_updater/diagnostic_updater.h> 00024 #include <diagnostic_updater/publisher.h> 00025 00026 #include <socketcan_interface/socketcan.h> 00027 #include <socketcan_interface/threading.h> 00028 00029 struct BmsParameter 00030 { 00031 unsigned int offset; 00032 unsigned int length; 00033 00034 bool is_signed; 00035 00036 ros::Publisher publisher; 00037 00038 diagnostic_msgs::KeyValue kv; 00039 00040 virtual ~BmsParameter() {} 00041 00042 virtual void update(const can::Frame &f) = 0; 00043 virtual void advertise(ros::NodeHandle &nh, const std::string &topic) = 0; 00044 00045 typedef boost::shared_ptr<BmsParameter> Ptr; 00046 }; 00047 00048 class CobBmsDriverNode 00049 { 00050 private: 00051 ros::NodeHandle nh_; 00052 ros::NodeHandle nh_priv_; 00053 00054 typedef std::multimap<uint8_t, BmsParameter::Ptr> ConfigMap; 00055 00056 //ROS parameters 00057 ConfigMap config_map_; //holds all the information that is provided in the configuration file 00058 int poll_period_for_two_ids_in_ms_; 00059 std::string can_device_; 00060 int bms_id_to_poll_; 00061 ros::Timer updater_timer_; 00062 00063 boost::mutex data_mutex_; 00064 00065 //polling lists that contain CAN-ID(s) that are to be polled. Each CAN-ID corresponds to a group of BMS parameters 00066 std::vector<uint8_t> polling_list1_; 00067 std::vector<uint8_t> polling_list2_; 00068 std::vector<uint8_t>::iterator polling_list1_it_; 00069 std::vector<uint8_t>::iterator polling_list2_it_; 00070 00071 //interface to send and recieve CAN frames 00072 can::ThreadedSocketCANInterface socketcan_interface_; 00073 00074 //pointer to callback function to handle CAN frames from BMS 00075 can::CommInterface::FrameListener::Ptr frame_listener_; 00076 00077 //diagnostics data received from BMS 00078 diagnostic_updater::DiagnosticStatusWrapper stat_; 00079 00080 //function to get ROS parameters from parameter server 00081 bool getParams(); 00082 00083 //function to interpret the diagnostics XmlRpcValue and save data in config_map_ 00084 bool loadConfigMap(XmlRpc::XmlRpcValue &diagnostics, std::vector<std::string> &topics); 00085 00086 //helper function to evaluate poll period from given poll frequency 00087 void evaluatePollPeriodFrom(int poll_frequency); 00088 00089 //function that goes through config_map_ and fills polling_list1_ and polling_list2_ with CAN-IDs. 00090 //If Topics are found on ROS Parameter Server, they are kept in a separate list (to be polled faster). 00091 //Otherwise, all CAN-ID are divided between both lists. 00092 void optimizePollingLists(); 00093 00094 //function that polls BMS (bms_id_to_poll_ is used here!). 00095 //Also, this function sleeps for time given by poll_period_for_two_ids_in_ms_ to ensure BMS is polled at the desired frequency 00096 void pollBmsForIds(const uint16_t first_id, const uint16_t second_id); 00097 00098 //callback function to handle all types of frames received from BMS 00099 void handleFrames(const can::Frame &f); 00100 00101 //updates the diagnostics data with the new data received from BMS 00102 void produceDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat); 00103 00104 //calls update function of diagnostics_updater 00105 void diagnosticsTimerCallback(const ros::TimerEvent&); 00106 public: 00107 00108 //updater for diagnostics data 00109 diagnostic_updater::Updater updater_; 00110 00111 CobBmsDriverNode(); 00112 ~CobBmsDriverNode(); 00113 00114 //initlializes SocketCAN interface, saves data from ROS parameter server, loads polling lists and sets up diagnostic updater 00115 bool prepare(); 00116 00117 //cycles through polling lists and sends 2 ids at a time (one from each list) to the BMS 00118 void pollNextInLists(); 00119 }; 00120 00121 00122 #endif //COB_BMS_DRIVER_NODE_H