Go to the documentation of this file.
18 #include <std_msgs/Float64.h>
19 #include <std_msgs/Int64.h>
20 #include <std_msgs/UInt64.h>
21 #include <std_msgs/Bool.h>
26 #include <boost/format.hpp>
30 using boost::make_shared;
41 big_endian_to_host<sizeof(T)>(&
f.data[offset], &res);
48 data =
param.is_signed ? read_value<int8_t> (
f,
param.offset) : read_value<uint8_t> (
f,
param.offset);
52 data =
param.is_signed ? read_value<int16_t> (
f,
param.offset) : read_value<uint16_t> (
f,
param.offset);
56 data =
param.is_signed ? read_value<int32_t> (
f,
param.offset) : read_value<uint32_t> (
f,
param.offset);
89 std::stringstream sstream;
90 sstream << std::setprecision(2) <<
msg_.data;
91 kv.value = sstream.str();
101 kv.value = (boost::format(
"%lld") %
msg_.data).str();
111 kv.value = (boost::format(
"%llu") %
msg_.data).str();
124 kv.value =
msg_.data ?
"True" :
"False";
144 ROS_ERROR(
"Could not prepare driver for start up");
161 ROS_ERROR(
"cob_bms_driver initialization failed");
176 std::vector <std::string> topics;
177 int poll_frequency_hz;
185 ROS_INFO(
"Topic list is empty. No publisher created");
203 for(std::vector<std::string>::iterator it = topics.begin(); it != topics.end(); ++it){
211 ROS_INFO_STREAM(
"Did not find \"can_device\" on parameter server. Using default value: can0");
217 ROS_INFO_STREAM(
"Did not find \"bms_id_to_poll\" on parameter server. Using default value: 0x200");
223 ROS_INFO_STREAM(
"Did not find \"poll_frequency\" on parameter server. Using default value: 20 Hz");
224 poll_frequency_hz = 20;
234 for (
size_t i = 0; i < diagnostics.
size(); ++i)
247 id =
static_cast<uint8_t
>(
static_cast<int>(config[
"id"]));
250 bool publishes =
false;
252 for(int32_t j=0; j<fields.
size(); ++j)
256 ROS_ERROR_STREAM(
"diagnostics[" << i <<
"]: fields[" << j <<
"]: name is missing.");
259 std::string name =
static_cast<std::string
>(field[
"name"]);
262 ROS_ERROR_STREAM(
"diagnostics[" << i <<
"]: fields[" << j <<
"]: len is missing.");
265 int len =
static_cast<int>(field[
"len"]);
269 int bit_mask =
static_cast<int>(field[
"bit_mask"]);
270 if(bit_mask & ~((1<<(len*8))-1)){
271 ROS_ERROR_STREAM(
"diagnostics[" << i <<
"]: fields[" << j <<
"]: bit_mask does fit not into type of length " << len);
274 entry = make_shared<BooleanBmsParameter>(bit_mask);
275 entry->kv.key = name;
278 ROS_ERROR_STREAM(
"diagnostics[" << i <<
"]: fields[" << j <<
"]: is_signed is missing.");
284 factor =
static_cast<double>(field[
"factor"]);
287 entry = make_shared<FloatBmsParameter>(factor);
289 entry->is_signed =
static_cast<bool>(field[
"is_signed"]);
292 entry->kv.key = name +
"[" +
static_cast<std::string
>(field[
"unit"]) +
"]";
294 entry->kv.key = name;
297 if(
static_cast<bool>(field[
"is_signed"])){
298 entry = make_shared<IntBmsParameter>();
300 entry = make_shared<UIntBmsParameter>();
302 entry->is_signed =
static_cast<bool>(field[
"is_signed"]);
303 entry->kv.key = name;
308 ROS_ERROR_STREAM(
"diagnostics[" << i <<
"]: fields[" << j <<
"]: offset is missing.");
311 entry->offset =
static_cast<int>(field[
"offset"]);
315 std::vector<std::string>::iterator topic_it = find(topics.begin(), topics.end(), name);
316 if(topic_it != topics.end()){
318 topics.erase(topic_it);
329 ROS_INFO_STREAM(
"Got "<< fields.
size() <<
" BmsParameter(s) with CAN-ID: 0x" << std::hex << (
unsigned int)
id << std::dec);
338 if ((poll_frequency_hz < 0) && (poll_frequency_hz > 20))
340 ROS_WARN_STREAM(
"Invalid ROS parameter value: poll_frequency_hz = "<< poll_frequency_hz <<
". Setting poll_frequency_hz to 20 Hz");
341 poll_frequency_hz = 20;
369 f.data[0] = first_id >> 8;
370 f.data[1] = first_id & 0xff;
371 f.data[2] = second_id >> 8;
372 f.data[3] = second_id & 0xff;
391 ROS_DEBUG_STREAM(
"polling BMS for CAN-IDs: 0x" << std::hex << (
int)first_id <<
" and 0x" << (
int) second_id << std::dec);
406 std::pair<ConfigMap::iterator, ConfigMap::iterator> range =
config_map_.equal_range(
f.id);
408 for (; range.first != range.second; ++range.first)
410 range.first->second->update(
f);
425 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Driver State: Closed");
429 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Driver State: Opened");
433 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
"Driver State: Ready");
437 stat.
summary(diagnostic_msgs::DiagnosticStatus::ERROR,
"Driver State: Unknown");
443 stat.values.push_back(cm_it->second->kv);
458 int main(
int argc,
char **argv)
460 ros::init(argc, argv,
"bms_driver_node");
464 if (!cob_bms_driver_node.
prepare())
return 1;
void update(const can::Frame &f)
void big_endian_to_host< 1 >(const void *in, void *out)
int main(int argc, char **argv)
can::CommInterface::FrameListenerConstSharedPtr frame_listener_
#define ROS_ERROR_STREAM(args)
void big_endian_to_host< 2 >(const void *in, void *out)
void add(const std::string &key, const bool &b)
void update(const can::Frame &f)
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
void produceDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
const std::string & getMessage() const
bool getParam(const std::string &key, bool &b) const
bool readTypedValue(const can::Frame &f, const BmsParameter ¶m, T &data)
can::ThreadedSocketCANInterface socketcan_interface_
ROSCPP_DECL void spinOnce()
void handleFrames(const can::Frame &f)
#define ROS_DEBUG_STREAM(args)
void update(const can::Frame &f)
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
bool loadConfigMap(XmlRpc::XmlRpcValue &diagnostics, std::vector< std::string > &topics)
#define ROS_WARN_STREAM(args)
virtual bool init(const std::string &device, bool loopback) override
void summary(const diagnostic_msgs::DiagnosticStatus &src)
ros::Timer updater_timer_
diagnostic_updater::Updater updater_
void big_endian_to_host(const void *in, void *out)
virtual void advertise(ros::NodeHandle &nh, const std::string &topic)
int poll_period_for_two_ids_in_ms_
boost::system::error_code error_code
#define ROS_INFO_STREAM(args)
diagnostic_updater::DiagnosticStatusWrapper stat_
void setHardwareID(const std::string &hwid)
void diagnosticsTimerCallback(const ros::TimerEvent &)
void big_endian_to_host< 8 >(const void *in, void *out)
std::vector< uint8_t > polling_list2_
void update(const can::Frame &f)
bool hasMember(const std::string &name) const
std::vector< uint8_t >::iterator polling_list1_it_
void big_endian_to_host< 4 >(const void *in, void *out)
FloatBmsParameter(double factor)
diagnostic_msgs::KeyValue kv
std::vector< uint8_t >::iterator polling_list2_it_
std::vector< uint8_t > polling_list1_
T param(const std::string ¶m_name, const T &default_val)
void optimizePollingLists()
enum can::State::DriverState driver_state
void evaluatePollPeriodFrom(int poll_frequency)
void pollBmsForIds(const uint16_t first_id, const uint16_t second_id)
void add(const std::string &name, TaskFunction f)
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
unsigned int internal_error
T read_value(const can::Frame &f, uint8_t offset)
BooleanBmsParameter(int bit_mask)
cob_bms_driver
Author(s): mig-mc
, Mathias Lüdtke
autogenerated on Wed Nov 8 2023 03:47:34