40 dbc_(dbc_file), offline_(offline)
48 dbc_(dbc_file), offline_(offline)
60 if (!(buffer.size() <= 64)) {
61 ROS_WARN(
"unsignedSignalData(): Buffer too large: %zu bytes", buffer.size());
66 ROS_WARN(
"unsignedSignalData(): Start bit out of range: Bit %d", sig_props.
start_bit);
72 ROS_WARN(
"unsignedSignalData(): Bit length out of range: %d bits", sig_props.
length);
77 ROS_WARN(
"unsignedSignalData(): Invalid bit order: %d", sig_props.
order);
81 uint16_t start_bit = (uint16_t)sig_props.
start_bit;
82 uint8_t length_bits = (uint16_t)sig_props.
length;
86 uint8_t bits_remaining = length_bits;
87 uint16_t current_bit = start_bit;
88 while (bits_remaining > 0) {
89 uint16_t next_bit_multiple = (((current_bit + 8) / 8) * 8);
90 uint16_t prev_bit_multiple = ((current_bit / 8) * 8);
91 uint8_t bits_to_consume = (lsb_order) ? (next_bit_multiple - current_bit) : (current_bit + 1 - prev_bit_multiple);
92 bits_to_consume = (bits_to_consume <= bits_remaining) ? bits_to_consume : bits_remaining;
93 uint8_t mask_shift = (lsb_order) ? (current_bit - prev_bit_multiple) : (current_bit + 1 - bits_to_consume - prev_bit_multiple);
94 uint8_t mask = (((1 << bits_to_consume) - 1) << mask_shift);
95 uint16_t value_shift = (lsb_order) ? (length_bits - bits_remaining) : (bits_remaining - bits_to_consume);
96 if (!((current_bit / 8) < buffer.size())) {
97 ROS_WARN(
"unsignedSignalData(): Calculated bit index exceeds buffer length: Bit %u: Max %zu", current_bit, ((buffer.size() * 8) - 1));
100 value |= ((((uint64_t)(buffer[current_bit / 8]) & mask) >> mask_shift) << value_shift);
101 bits_remaining -= bits_to_consume;
103 current_bit += bits_to_consume;
105 if ((current_bit + 1 - bits_to_consume) % 8 == 0) {
106 current_bit = (((current_bit / 8) * 8) + 15);
109 assert(bits_remaining == 0);
110 current_bit -= bits_to_consume;
122 if (sig_props.length != 64) {
123 value |= (value & (1ul << (sig_props.length - 1))) ? (((1ul << (64 - sig_props.length)) - 1) << sig_props.length) : 0;
125 return (int64_t)value;
142 if (sig_props.length >= 64) {
148 if ((sig_props.sign ==
SIGNED)) {
149 max_val = (((int64_t)1 << (sig_props.length - 1)) - 1);
150 min_val = -((int64_t)1 << (sig_props.length - 1));
152 max_val = (((int64_t)1 << sig_props.length) - 1);
155 max_val = max_val * (int64_t)sig_props.factor + (int64_t)sig_props.offset;
156 min_val = min_val * (int64_t)sig_props.factor + (int64_t)sig_props.offset;
157 if (max_val < min_val) {
158 std::swap(min_val, max_val);
162 if ((INT8_MIN <= min_val) && (max_val <= INT8_MAX)) {
164 }
else if ((INT16_MIN <= min_val) && (max_val <= INT16_MAX)) {
166 }
else if ((INT32_MIN <= min_val) && (max_val <= INT32_MAX)) {
172 if (max_val <= UINT8_MAX) {
174 }
else if (max_val <= UINT16_MAX) {
176 }
else if (max_val <= UINT32_MAX) {
188 if (it->getId() == can_msg.id) {
189 can_msg.msg_name = it->getName();
192 RosCanSigStruct new_sig;
193 new_sig.factor = m_it->getFactor();
194 new_sig.length = m_it->getLength();
195 new_sig.maximum = m_it->getMaximum();
196 new_sig.minimum = m_it->getMinimum();
197 new_sig.offset = m_it->getOffset();
198 new_sig.order = m_it->getByteOrder();
199 new_sig.sig_name = m_it->getName();
200 new_sig.sign = m_it->getSign();
201 new_sig.start_bit = m_it->getStartbit();
202 new_sig.multiplexor = m_it->getMultiplexor();
203 new_sig.multiplexNum = m_it->getMultiplexedNumber();
204 can_msg.sigs.push_back(new_sig);
207 msgs_[can_msg.id] = can_msg;
215 std::stringstream ss;
216 ss <<
"x" << std::hex << std::setfill(
'0') << std::setw(3) << can_msg.id;
217 can_msg.msg_name = ss.str();
218 msgs_[can_msg.id] = can_msg;
221 ROS_WARN(
"Received unknown CAN message with ID = 0x%X", can_msg.id);
224 can_msg =
msgs_[can_msg.id];
234 info.message_pub = nh.
advertise<can_msgs::Frame>(info.msg_name, 1);
237 ROS_DEBUG(
"Initializing publishers for %zu signals...", info.sigs.size());
238 for (
size_t i=0; i<info.sigs.size(); i++){
243 msgs_[info.id] = info;
269 const uint32_t QUEUE_SIZE = 10;
270 if (info.length == 1) {
271 info.sig_pub = nh.
advertise<std_msgs::Bool>(info.sig_name, QUEUE_SIZE);
272 }
else if ((fmod(info.factor, 1.0) != 0) || (fmod(info.offset, 1.0) != 0)) {
273 info.sig_pub = nh.
advertise<std_msgs::Float64>(info.sig_name, QUEUE_SIZE);
275 if ((info.sign ==
SIGNED) || (info.offset < 0) || (info.factor < 0)) {
277 case 8: info.sig_pub = nh.
advertise<std_msgs::Int8 >(info.sig_name, QUEUE_SIZE);
break;
278 case 16: info.sig_pub = nh.
advertise<std_msgs::Int16>(info.sig_name, QUEUE_SIZE);
break;
279 case 32: info.sig_pub = nh.
advertise<std_msgs::Int32>(info.sig_name, QUEUE_SIZE);
break;
280 case 64: info.sig_pub = nh.
advertise<std_msgs::Int64>(info.sig_name, QUEUE_SIZE);
break;
284 case 8: info.sig_pub = nh.
advertise<std_msgs::UInt8 >(info.sig_name, QUEUE_SIZE);
break;
285 case 16: info.sig_pub = nh.
advertise<std_msgs::UInt16>(info.sig_name, QUEUE_SIZE);
break;
286 case 32: info.sig_pub = nh.
advertise<std_msgs::UInt32>(info.sig_name, QUEUE_SIZE);
break;
287 case 64: info.sig_pub = nh.
advertise<std_msgs::UInt64>(info.sig_name, QUEUE_SIZE);
break;
297 ROS_DEBUG(
"Opening bag file for writing...");
306 ROS_DEBUG(
" Publishing value (%s): %f", info.sigs[i].sig_name.c_str(), (
double)sig_msg.data);
307 if (i < info.sigs.size()) {
309 writeToBag(info.msg_name +
"/" + info.sigs[i].sig_name, stamp, sig_msg);
311 info.sigs[i].sig_pub.publish(sig_msg);
320 info.message_pub.publish(msg);
328 info.message_pub.publish(msg);
335 unsigned short multiplexorValue = -1;
336 for (
size_t i = 0; i < info.sigs.size(); i++) {
344 for (
size_t i = 0; i < info.sigs.size(); i++) {
347 ROS_DEBUG(
"MSG Name: %s", info.sigs[i].sig_pub.getTopic().c_str());
350 if (info.sigs[i].multiplexNum != multiplexorValue) {
351 ROS_DEBUG(
" Skipping multiplexed value...");
357 if (info.sigs[i].length == 1) {
358 pubCanSig(info, buildMsg<std_msgs::Bool>(info.sigs[i], buffer,
false), stamp, i);
359 }
else if ((fmod(info.sigs[i].factor, 1.0) != 0) || fmod(info.sigs[i].offset, 1.0) != 0) {
360 pubCanSig(info, buildMsg<std_msgs::Float64>(info.sigs[i], buffer, info.sigs[i].sign ==
SIGNED), stamp, i);
362 if ((info.sigs[i].sign ==
SIGNED) || (info.sigs[i].offset < 0) || (info.sigs[i].factor < 0)) {
363 if (info.sigs[i].sign ==
SIGNED) {
365 case 8:
pubCanSig(info, buildMsg<std_msgs::Int8 >(info.sigs[i], buffer,
true), stamp, i);
break;
366 case 16:
pubCanSig(info, buildMsg<std_msgs::Int16>(info.sigs[i], buffer,
true), stamp, i);
break;
367 case 32:
pubCanSig(info, buildMsg<std_msgs::Int32>(info.sigs[i], buffer,
true), stamp, i);
break;
368 case 64:
pubCanSig(info, buildMsg<std_msgs::Int64>(info.sigs[i], buffer,
true), stamp, i);
break;
372 case 8:
pubCanSig(info, buildMsg<std_msgs::Int8 >(info.sigs[i], buffer,
false), stamp, i);
break;
373 case 16:
pubCanSig(info, buildMsg<std_msgs::Int16>(info.sigs[i], buffer,
false), stamp, i);
break;
374 case 32:
pubCanSig(info, buildMsg<std_msgs::Int32>(info.sigs[i], buffer,
false), stamp, i);
break;
375 case 64:
pubCanSig(info, buildMsg<std_msgs::Int64>(info.sigs[i], buffer,
false), stamp, i);
break;
380 case 8:
pubCanSig(info, buildMsg<std_msgs::UInt8 >(info.sigs[i], buffer,
false), stamp, i);
break;
381 case 16:
pubCanSig(info, buildMsg<std_msgs::UInt16>(info.sigs[i], buffer,
false), stamp, i);
break;
382 case 32:
pubCanSig(info, buildMsg<std_msgs::UInt32>(info.sigs[i], buffer,
false), stamp, i);
break;
383 case 64:
pubCanSig(info, buildMsg<std_msgs::UInt64>(info.sigs[i], buffer,
false), stamp, i);
break;
393 const uint32_t
id = msg.id | (msg.is_extended ? 0x80000000 : 0x00000000);
395 ROS_WARN(
"Skipping unknown message ID: 0x%03X",
id);
398 const RosCanMsgStruct &info =
msgs_[id];
405 pubCanMsgSignals(info, std::vector<uint8_t>(msg.data.begin(), msg.data.end()), stamp);
412 const uint32_t
id = msg.id | (msg.extended ? 0x80000000 : 0x00000000);
414 ROS_WARN(
"Skipping unknown message ID: 0x%03X",
id);
417 const RosCanMsgStruct &info =
msgs_[id];