cob_bms_driver_node.cpp
Go to the documentation of this file.
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 #include <std_msgs/Float64.h>
00019 #include <std_msgs/Int64.h>
00020 #include <std_msgs/UInt64.h>
00021 #include <std_msgs/Bool.h>
00022 #include <XmlRpcException.h>
00023 
00024 #include <stdint.h>
00025 #include <endian.h>
00026 #include <boost/format.hpp>
00027 
00028 #include <cob_bms_driver/cob_bms_driver_node.h>
00029 
00030 using boost::make_shared;
00031 
00032 //template to be used to read CAN frames received from the BMS
00033 template<int N> void big_endian_to_host(const void* in, void* out);
00034 template<> void big_endian_to_host<1>(const void* in, void* out){ *(uint8_t*)out = *(uint8_t*)in;}
00035 template<> void big_endian_to_host<2>(const void* in, void* out){ *(uint16_t*)out = be16toh(*(uint16_t*)in);}
00036 template<> void big_endian_to_host<4>(const void* in, void* out){ *(uint32_t*)out = be32toh(*(uint32_t*)in);}
00037 template<> void big_endian_to_host<8>(const void* in, void* out){ *(uint64_t*)out = be64toh(*(uint64_t*)in);}
00038 
00039 template<typename T> T read_value(const can::Frame &f, uint8_t offset){
00040     T res;
00041     big_endian_to_host<sizeof(T)>(&f.data[offset], &res);
00042     return res;
00043 }
00044 template<typename T> bool readTypedValue(const can::Frame &f, const BmsParameter &param, T &data){
00045     switch (param.length)
00046     {
00047     case 1:
00048         data = param.is_signed ? read_value<int8_t> (f, param.offset) : read_value<uint8_t> (f, param.offset);
00049         break;
00050 
00051     case 2:
00052         data = param.is_signed ? read_value<int16_t> (f, param.offset) : read_value<uint16_t> (f, param.offset);
00053         break;
00054 
00055     case 4:
00056         data = param.is_signed ? read_value<int32_t> (f, param.offset) : read_value<uint32_t> (f, param.offset);
00057         break;
00058 
00059     default:
00060             ROS_WARN_STREAM("Unknown length of BmsParameter: " << param.kv.key << ". Cannot read data!");
00061             return false;
00062     }
00063     return true;
00064 }
00065 
00066 template<typename T> struct TypedBmsParameter : BmsParameter {
00067     T msg_;
00068 
00069     void publish(){
00070         //if the BmsParameter is a topic, publish data to the topic
00071         if (static_cast<void*>(publisher))
00072         {
00073             publisher.publish(msg_);
00074         }
00075     }
00076     virtual void advertise(ros::NodeHandle &nh, const std::string &topic){
00077         publisher = nh.advertise<T> (topic, 1, true);
00078     }
00079 };
00080 
00081 struct FloatBmsParameter : TypedBmsParameter<std_msgs::Float64> {
00082     double factor;
00083     FloatBmsParameter(double factor) : factor(factor) {}
00084     void update(const can::Frame &f){
00085         readTypedValue(f, *this, msg_.data);
00086         msg_.data *= factor;
00087 
00088         //save data for diagnostics updater (and round to two digits for readability)
00089         kv.value = (boost::format("%.2f") % msg_.data).str();
00090         publish();
00091     }
00092 };
00093 
00094 struct IntBmsParameter : TypedBmsParameter<std_msgs::Int64> {
00095     IntBmsParameter() {}
00096     void update(const can::Frame &f){
00097         readTypedValue(f, *this, msg_.data);
00098 
00099         kv.value = (boost::format("%lld") % msg_.data).str();
00100         publish();
00101     }
00102 };
00103 
00104 struct UIntBmsParameter : TypedBmsParameter<std_msgs::UInt64> {
00105     UIntBmsParameter() {}
00106     void update(const can::Frame &f){
00107         readTypedValue(f, *this, msg_.data);
00108 
00109         kv.value = (boost::format("%llu") % msg_.data).str();
00110         publish();
00111     }
00112 };
00113 
00114 struct BooleanBmsParameter : TypedBmsParameter<std_msgs::Bool> {
00115     int bit_mask;
00116     BooleanBmsParameter(int bit_mask) : bit_mask(bit_mask) { is_signed = true; }
00117     void update(const can::Frame &f){
00118         int value;
00119         readTypedValue(f, *this, value);
00120         msg_.data = (value & bit_mask) == bit_mask;
00121 
00122         kv.value = msg_.data ? "True" : "False";
00123         publish();
00124     }
00125 };
00126 
00127 CobBmsDriverNode::CobBmsDriverNode()
00128 : nh_priv_("~")
00129 {}
00130 
00131 CobBmsDriverNode::~CobBmsDriverNode()
00132 {
00133     socketcan_interface_.shutdown();
00134 }
00135 
00136 //initlializes SocketCAN interface, saves data from ROS parameter server, loads polling lists and sets up diagnostic updater
00137 bool CobBmsDriverNode::prepare()
00138 {
00139     //reads parameters from ROS parameter server and saves them in respective member variable: config_map_, poll_period_for_two_ids_in_ms_, can_device_, bms_id_to_poll_
00140     if (!getParams())
00141     {
00142         ROS_ERROR("Could not prepare driver for start up");
00143         return false;
00144     }
00145 
00146     optimizePollingLists();
00147 
00148     //initalize polling lists iterators
00149     polling_list1_it_ = polling_list1_.begin();
00150     polling_list2_it_ = polling_list2_.begin();
00151 
00152     updater_.setHardwareID("bms");
00153     updater_.add("cob_bms_dagnostics_updater", this, &CobBmsDriverNode::produceDiagnostics);
00154 
00155     updater_timer_ = nh_.createTimer(ros::Duration(updater_.getPeriod()), &CobBmsDriverNode::diagnosticsTimerCallback, this);
00156 
00157     //initialize the socketcan interface
00158     if(!socketcan_interface_.init(can_device_, false)) {
00159         ROS_ERROR("cob_bms_driver initialization failed");
00160         return false;
00161     }
00162 
00163     //create listener for CAN frames
00164     frame_listener_  = socketcan_interface_.createMsgListener(can::CommInterface::FrameDelegate(this, &CobBmsDriverNode::handleFrames));
00165 
00166     return true;
00167 }
00168 
00169 //function to get ROS parameters from parameter server
00170 bool CobBmsDriverNode::getParams()
00171 {
00172     //local declarations
00173     XmlRpc::XmlRpcValue diagnostics;
00174     std::vector <std::string> topics;
00175     int poll_frequency_hz;
00176 
00177     if (!nh_priv_.getParam("topics", topics))
00178     {
00179         ROS_INFO_STREAM("Did not find \"topics\" on parameter server");
00180     }
00181     if (topics.empty())
00182     {
00183         ROS_INFO("Topic list is empty. No publisher created");
00184     }
00185 
00186     if (!nh_priv_.getParam("diagnostics", diagnostics))
00187     {
00188         ROS_ERROR_STREAM("Did not find \"diagnostics\" on parameter server");
00189         return false;
00190     }
00191     try {
00192         if(!loadConfigMap(diagnostics, topics)) return false;
00193     }
00194     catch(XmlRpc::XmlRpcException &e){
00195         ROS_ERROR_STREAM("Could not parse 'diagnostics': "<< e.getMessage());
00196         return false;
00197     }
00198 
00199     if (!topics.empty())
00200     {
00201         for(std::vector<std::string>::iterator it = topics.begin(); it != topics.end(); ++it){
00202             ROS_ERROR_STREAM("Could not find entry for topic '" << *it << "'.");
00203         }
00204         return false;
00205     }
00206 
00207     if (!nh_priv_.getParam("can_device", can_device_))
00208     {
00209         ROS_INFO_STREAM("Did not find \"can_device\" on parameter server. Using default value: can0");
00210         can_device_ = "can0";
00211     }
00212 
00213     if (!nh_priv_.getParam("bms_id_to_poll", bms_id_to_poll_))
00214     {
00215         ROS_INFO_STREAM("Did not find \"bms_id_to_poll\" on parameter server. Using default value: 0x200");
00216         bms_id_to_poll_ = 0x200;
00217     }
00218 
00219     if (!nh_priv_.getParam("poll_frequency_hz", poll_frequency_hz))
00220     {
00221         ROS_INFO_STREAM("Did not find \"poll_frequency\" on parameter server. Using default value: 20 Hz");
00222         poll_frequency_hz = 20;
00223     }
00224     evaluatePollPeriodFrom(poll_frequency_hz);
00225     return true;
00226 }
00227 
00228 //function to interpret the diagnostics XmlRpcValue and save data in config_map_
00229 bool CobBmsDriverNode::loadConfigMap(XmlRpc::XmlRpcValue &diagnostics, std::vector<std::string> &topics)
00230 {
00231     //for each id in list of ids
00232     for (size_t i = 0; i < diagnostics.size(); ++i)
00233     {
00234         uint8_t id;
00235         XmlRpc::XmlRpcValue config = diagnostics[i];
00236 
00237         if(!config.hasMember("id")) {
00238             ROS_ERROR_STREAM("diagnostics[" << i << "]: id is missing.");
00239             return false;
00240         }
00241         if(!config.hasMember("fields")) {
00242             ROS_ERROR_STREAM("diagnostics[" << i << "]: fields is missing.");
00243             return false;
00244         }
00245         id = static_cast<uint8_t>(static_cast<int>(config["id"]));
00246 
00247         XmlRpc::XmlRpcValue fields = config["fields"];
00248         bool publishes = false;
00249 
00250         for(int32_t j=0; j<fields.size(); ++j)
00251         {
00252             XmlRpc::XmlRpcValue field = fields[j];
00253             if(!field.hasMember("name")){
00254                 ROS_ERROR_STREAM("diagnostics[" << i << "]: fields[" << j << "]: name is missing.");
00255                 return false;
00256             }
00257             std::string name = static_cast<std::string>(field["name"]);
00258 
00259             if(!field.hasMember("len")){
00260                 ROS_ERROR_STREAM("diagnostics[" << i << "]: fields[" << j << "]: len is missing.");
00261                 return false;
00262             }
00263             int len = static_cast<int>(field["len"]);
00264 
00265             BmsParameter::Ptr entry;
00266             if(field.hasMember("bit_mask")){
00267                 int bit_mask = static_cast<int>(field["bit_mask"]);
00268                 if(bit_mask & ~((1<<(len*8))-1)){
00269                     ROS_ERROR_STREAM("diagnostics[" << i << "]: fields[" << j << "]: bit_mask does fit not into type of length " << len);
00270                     return false;
00271                 }
00272                 entry = make_shared<BooleanBmsParameter>(bit_mask);
00273                 entry->kv.key = name;
00274             }else{
00275                 if(!field.hasMember("is_signed")){
00276                     ROS_ERROR_STREAM("diagnostics[" << i << "]: fields[" << j << "]: is_signed is missing.");
00277                     return false;
00278                 }
00279                 if(field.hasMember("factor")){
00280                     double factor = 1.0;
00281                     if(field.hasMember("factor")){
00282                         factor = static_cast<double>(field["factor"]);
00283                     }
00284 
00285                     entry = make_shared<FloatBmsParameter>(factor);
00286 
00287                     entry->is_signed = static_cast<bool>(field["is_signed"]);
00288 
00289                     if(field.hasMember("unit")){
00290                         entry->kv.key = name + "[" + static_cast<std::string>(field["unit"]) + "]";
00291                     }else{
00292                         entry->kv.key = name;
00293                     }
00294                 }else{
00295                     if(static_cast<bool>(field["is_signed"])){
00296                         entry = make_shared<IntBmsParameter>();
00297                     }else{
00298                         entry = make_shared<UIntBmsParameter>();
00299                     }
00300                     entry->is_signed = static_cast<bool>(field["is_signed"]);
00301                     entry->kv.key = name;
00302                 }
00303             }
00304 
00305             if(!field.hasMember("offset")){
00306                 ROS_ERROR_STREAM("diagnostics[" << i << "]: fields[" << j << "]: offset is missing.");
00307                 return false;
00308             }
00309             entry->offset = static_cast<int>(field["offset"]);
00310 
00311             entry->length = len;
00312 
00313             std::vector<std::string>::iterator topic_it = find(topics.begin(), topics.end(), name);
00314             if(topic_it != topics.end()){
00315                 entry->advertise(nh_priv_, name);
00316                 topics.erase(topic_it);
00317                 publishes = true;
00318                 ROS_INFO_STREAM("Created publisher for: " << name);
00319             }
00320 
00321             config_map_.insert(std::make_pair(id, entry));
00322 
00323         }
00324         if(publishes) polling_list1_.push_back(id);
00325         else polling_list2_.push_back(id);
00326 
00327         ROS_INFO_STREAM("Got "<< fields.size() << " BmsParameter(s) with CAN-ID: 0x" << std::hex << (unsigned int) id << std::dec);
00328     }
00329     return true;
00330 }
00331 
00332 //helper function to evaluate poll period from given poll frequency
00333 void CobBmsDriverNode::evaluatePollPeriodFrom(int poll_frequency_hz)
00334 {
00335     //check the validity of given poll_frequency_hz
00336     if ((poll_frequency_hz < 0) && (poll_frequency_hz > 20))
00337     {
00338         ROS_WARN_STREAM("Invalid ROS parameter value: poll_frequency_hz = "<< poll_frequency_hz << ". Setting poll_frequency_hz to 20 Hz");
00339         poll_frequency_hz = 20;
00340     }
00341     //now evaluate and save poll period
00342     poll_period_for_two_ids_in_ms_ = (1/double(poll_frequency_hz))*1000;
00343     ROS_INFO_STREAM("Evaluated polling period: "<< poll_period_for_two_ids_in_ms_ << " ms");
00344 }
00345 
00346 //function that goes through config_map_ and fills polling_list1_ and polling_list2_. If topics are found on ROS Parameter Server, they are kept in list1 otherwise, all parameter id are divided between both lists.
00347 void CobBmsDriverNode::optimizePollingLists()
00348 {
00349     if(polling_list1_.size() == 0){ // no topics, so just distribute topics
00350         while(polling_list1_.size() < polling_list2_.size()){
00351             polling_list1_.push_back(polling_list2_.back());
00352             polling_list2_.pop_back();
00353         }
00354     }else{
00355         while(polling_list1_.size() > polling_list2_.size()){
00356             polling_list2_.push_back(polling_list1_.back());
00357             polling_list1_.pop_back();
00358         }
00359     }
00360     ROS_INFO_STREAM("Loaded \'"<< polling_list1_.size() << "\' CAN-ID(s) in polling_list1_ and \'"<< polling_list2_.size() <<"\' CAN-ID(s) in polling_list2_");
00361 }
00362 
00363 //function that polls BMS for given ids
00364 void CobBmsDriverNode::pollBmsForIds(const uint16_t first_id, const uint16_t second_id)
00365 {
00366     can::Frame f(can::Header(bms_id_to_poll_,false,false,false),4);
00367     f.data[0] = first_id >> 8;  //high_byte
00368     f.data[1] = first_id & 0xff;    //low_byte
00369     f.data[2] = second_id >> 8;
00370     f.data[3] = second_id & 0xff;
00371 
00372     socketcan_interface_.send(f);
00373 
00374     boost::this_thread::sleep_for(boost::chrono::milliseconds(poll_period_for_two_ids_in_ms_));
00375 }
00376 
00377 //cycles through polling lists and sends 2 ids at a time (one from each list) to the BMS
00378 void CobBmsDriverNode::pollNextInLists()
00379 {
00380     //restart if reached the end of polling lists
00381     if (polling_list1_it_ == polling_list1_.end()) polling_list1_it_ = polling_list1_.begin();
00382     if (polling_list2_it_ == polling_list2_.end()) polling_list2_it_ = polling_list2_.begin();
00383     //clear stat_, so that it can be refilled with new data
00384     stat_.clear();
00385 
00386     uint16_t first_id = (polling_list1_it_ == polling_list1_.end()) ? 0 : (*polling_list1_it_ | 0x0100);
00387     uint16_t second_id = (polling_list2_it_ == polling_list2_.end()) ? 0 : (*polling_list2_it_ | 0x0100);
00388 
00389     ROS_DEBUG_STREAM("polling BMS for CAN-IDs: 0x" << std::hex << (int)first_id << " and 0x" << (int) second_id << std::dec);
00390 
00391     pollBmsForIds(first_id,second_id);
00392 
00393     //increment iterators for next poll
00394     if (!polling_list1_.empty()) ++polling_list1_it_;
00395     if (!polling_list2_.empty()) ++polling_list2_it_;
00396 }
00397 
00398 //callback function to handle all types of frames received from BMS
00399 void CobBmsDriverNode::handleFrames(const can::Frame &f)
00400 {
00401     boost::mutex::scoped_lock lock(data_mutex_);
00402 
00403     //id to find in config map
00404     std::pair<ConfigMap::iterator, ConfigMap::iterator>  range = config_map_.equal_range(f.id);
00405 
00406     for (; range.first != range.second; ++range.first)
00407     {
00408         range.first->second->update(f);
00409     }
00410 }
00411 
00412 //updates the diagnostics data with the new data received from BMS
00413 void CobBmsDriverNode::produceDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
00414 {
00415     boost::mutex::scoped_lock lock(data_mutex_);
00416 
00417     can::State state = socketcan_interface_.getState();
00418     stat.add("error_code", state.error_code);
00419     stat.add("can_error_code", state.internal_error);
00420     switch (state.driver_state)
00421     {
00422     case can::State::closed:
00423         stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Driver State: Closed");
00424         break;
00425 
00426     case can::State::open:
00427         stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Driver State: Opened");
00428         break;
00429 
00430     case can::State::ready:
00431         stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Driver State: Ready");
00432         break;
00433 
00434     default:
00435         stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Driver State: Unknown");
00436         break;
00437     }
00438 
00439     for (ConfigMap::iterator cm_it = config_map_.begin(); cm_it != config_map_.end(); ++cm_it)
00440     {
00441                 stat.values.push_back(cm_it->second->kv);
00442     }
00443 }
00444 
00445 void CobBmsDriverNode::diagnosticsTimerCallback(const ros::TimerEvent& event)
00446 {
00447     //update diagnostics
00448     updater_.update();
00449     if(!socketcan_interface_.getState().isReady()){
00450         ROS_ERROR("Restarting BMS socketcan");
00451         socketcan_interface_.shutdown();
00452         socketcan_interface_.recover();
00453     }
00454 }
00455 
00456 int main(int argc, char **argv)
00457 {
00458     ros::init(argc, argv, "bms_driver_node");
00459 
00460     CobBmsDriverNode cob_bms_driver_node;
00461 
00462     if (!cob_bms_driver_node.prepare()) return 1;
00463 
00464     ROS_INFO("Started polling BMS...");
00465     while (ros::ok())
00466     {
00467         cob_bms_driver_node.pollNextInLists();
00468         ros::spinOnce();
00469     }
00470     return 0;
00471 }


cob_bms_driver
Author(s): mig-mc , Mathias Lüdtke
autogenerated on Sat Jun 8 2019 21:01:57