40 dbc_(dbc_file), offline_(offline)
61 if (sig_props.
length >= 64) {
62 mask = ((uint64_t) -1);
65 mask = (((uint64_t)1) << sig_props.
length) - 1;
70 return (raw_data >> sig_props.
start_bit) & mask;
74 return (__builtin_bswap64(raw_data) >> intel_start_bit) & mask;
81 if (sig_props.
length >= 64) {
82 mask = ((uint64_t) -1);
85 mask = (((uint64_t)1) << sig_props.
length) - 1;
90 if (val & (1 << (sig_props.
length - 1))) {
111 if (sig_props.
length >= 64) {
118 max_val = (((int64_t)1 << (sig_props.
length - 1)) - 1);
119 min_val = -((int64_t)1 << (sig_props.
length - 1));
121 max_val = (((int64_t)1 << sig_props.
length) - 1);
124 max_val = max_val * (int64_t)sig_props.
factor + (int64_t)sig_props.
offset;
125 min_val = min_val * (int64_t)sig_props.
factor + (int64_t)sig_props.
offset;
126 if (max_val < min_val) {
127 std::swap(min_val, max_val);
131 if ((INT8_MIN <= min_val) && (max_val <= INT8_MAX)) {
133 }
else if ((INT16_MIN <= min_val) && (max_val <= INT16_MAX)) {
135 }
else if ((INT32_MIN <= min_val) && (max_val <= INT32_MAX)) {
141 if (max_val <= UINT8_MAX) {
143 }
else if (max_val <= UINT16_MAX) {
145 }
else if (max_val <= UINT32_MAX) {
157 if (it->getId() == can_msg.
id) {
162 new_sig.
factor = m_it->getFactor();
163 new_sig.
length = m_it->getLength();
164 new_sig.
maximum = m_it->getMaximum();
165 new_sig.
minimum = m_it->getMinimum();
166 new_sig.
offset = m_it->getOffset();
167 new_sig.
order = m_it->getByteOrder();
169 new_sig.
sign = m_it->getSign();
173 can_msg.
sigs.push_back(new_sig);
184 std::stringstream ss;
185 ss <<
"x" << std::hex << std::setfill(
'0') << std::setw(3) << can_msg.
id;
190 ROS_WARN(
"Received unknown CAN message with ID = 0x%X", can_msg.
id);
206 ROS_DEBUG(
"Initializing publishers for %zu signals...", info.
sigs.size());
207 for (
size_t i=0; i<info.
sigs.size(); i++){
238 const uint32_t QUEUE_SIZE = 10;
241 }
else if ((fmod(info.
factor, 1.0) != 0) || (fmod(info.
offset, 1.0) != 0)) {
266 ROS_DEBUG(
"Opening bag file for writing...");
275 ROS_DEBUG(
" Publishing value (%s): %f", info.
sigs[i].sig_name.c_str(), (double)sig_msg.data);
276 if (i < info.
sigs.size()) {
280 info.
sigs[i].sig_pub.publish(sig_msg);
296 const uint32_t
id = msg.id | (msg.is_extended ? 0x80000000 : 0x00000000);
298 ROS_WARN(
"Skipping unknown message ID: 0x%03X",
id);
302 const uint64_t data = *((uint64_t*)&msg.data[0]);
311 unsigned short multiplexorValue = -1;
312 for (
size_t i = 0; i < info.
sigs.size(); i++) {
320 for (
size_t i = 0; i < info.
sigs.size(); i++) {
323 ROS_DEBUG(
"MSG Name: %s", info.
sigs[i].sig_pub.getTopic().c_str());
326 if (info.
sigs[i].multiplexNum != multiplexorValue) {
327 ROS_DEBUG(
" Skipping multiplexed value...");
333 if (info.
sigs[i].length == 1) {
334 pubCanSig(info, buildMsg<std_msgs::Bool>(info.
sigs[i], data,
false), stamp, i);
335 }
else if ((fmod(info.
sigs[i].factor, 1.0) != 0) || fmod(info.
sigs[i].offset, 1.0) != 0) {
338 if ((info.
sigs[i].sign ==
SIGNED) || (info.
sigs[i].offset < 0) || (info.
sigs[i].factor < 0)) {
341 case 8:
pubCanSig(info, buildMsg<std_msgs::Int8 >(info.
sigs[i], data,
true), stamp, i);
break;
342 case 16:
pubCanSig(info, buildMsg<std_msgs::Int16>(info.
sigs[i], data,
true), stamp, i);
break;
343 case 32:
pubCanSig(info, buildMsg<std_msgs::Int32>(info.
sigs[i], data,
true), stamp, i);
break;
344 case 64:
pubCanSig(info, buildMsg<std_msgs::Int64>(info.
sigs[i], data,
true), stamp, i);
break;
348 case 8:
pubCanSig(info, buildMsg<std_msgs::Int8 >(info.
sigs[i], data,
false), stamp, i);
break;
349 case 16:
pubCanSig(info, buildMsg<std_msgs::Int16>(info.
sigs[i], data,
false), stamp, i);
break;
350 case 32:
pubCanSig(info, buildMsg<std_msgs::Int32>(info.
sigs[i], data,
false), stamp, i);
break;
351 case 64:
pubCanSig(info, buildMsg<std_msgs::Int64>(info.
sigs[i], data,
false), stamp, i);
break;
356 case 8:
pubCanSig(info, buildMsg<std_msgs::UInt8 >(info.
sigs[i], data,
false), stamp, i);
break;
357 case 16:
pubCanSig(info, buildMsg<std_msgs::UInt16>(info.
sigs[i], data,
false), stamp, i);
break;
358 case 32:
pubCanSig(info, buildMsg<std_msgs::UInt32>(info.
sigs[i], data,
false), stamp, i);
break;
359 case 64:
pubCanSig(info, buildMsg<std_msgs::UInt64>(info.
sigs[i], data,
false), stamp, i);
break;
const_iterator end() const
void publish(const boost::shared_ptr< M > &message) const
void open(std::string const &filename, uint32_t mode=bagmode::Read)
void setCompression(CompressionType compression)
messages_t::const_iterator const_iterator
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
const_iterator begin() const
signals_t::const_iterator const_iterator
void write(std::string const &topic, ros::MessageEvent< T > const &event)