diff --git a/src/axis_imu.cc b/src/axis_imu.cc index 351194e0cec376ae2063b3403df651fba03d1660..9e7f6c286bd9964c6fb809402703535e47d09751 100644 --- a/src/axis_imu.cc +++ b/src/axis_imu.cc @@ -97,7 +97,9 @@ private: void handle_receive(const boost::system::error_code& error, std::size_t bytes_transferred) { if (!error || error == boost::asio::error::message_size) { + // MESSAGES SIZE: 91 bytes // cerr << "Got message: " << bytes_transferred << endl; + // cerr << "Got message: " << bytes_transferred << " - " << recv_buffer_[0] << " - " << recv_buffer_[33] << endl; // float time = bytesToFloat(recv_buffer_[1], recv_buffer_[2], recv_buffer_[3], recv_buffer_[4]); double gtime = bytesToDouble(1); @@ -283,7 +285,7 @@ int main(int argc, char *argv[]) { os << "http://" << camera_ip << "/local/motionloggerudp/control.cgi?cmd=start&target_ip=" << driver_ip << "&target_port=" << port - << "&accel_enabled=1&accel_rate_div=" << accel_div << "&gyro_enabled=1&gyro_rate_div=" << gyro_div; + << "&accel_enabled=1&accel_rate_div=" << accel_div << "&gyro_enabled=1&gyro_rate_div=" << gyro_div << "&pos_enabled=1"; std::string url = os.str(); ROS_INFO("COMMAND URL: %s", url.c_str());