提交 a13d35c4 编写于 作者: L Liangliang Zhang 提交者: Calvin Miao

driviers: fixed code issues in velodyne driver.

上级 41b07434
......@@ -757,17 +757,19 @@ bool NovatelParser::handle_raw_imu(const novatel::RawImu* imu) {
float imu_measurement_span = 1.0 / 200.0;
if (is_zero(_gyro_scale)) {
novatel::ImuParameter param = novatel::get_imu_parameter(
novatel::ImuType::ADIS16488);
//ROS_INFO_STREAM("IMU type: " << static_cast<unsigned>(imu->imu_type) << "; "
novatel::ImuParameter param =
novatel::get_imu_parameter(novatel::ImuType::ADIS16488);
// ROS_INFO_STREAM("IMU type: " << static_cast<unsigned>(imu->imu_type) <<
// "; "
// << "Gyro scale: " << param.gyro_scale << "; "
// << "Accel scale: " << param.accel_scale << "; "
// << "Sampling rate: " << param.sampling_rate_hz
// << "Accel scale: " << param.accel_scale << ";
// "
// << "Sampling rate: " <<
// param.sampling_rate_hz
// << ".");
if (is_zero(param.sampling_rate_hz)) {
ROS_ERROR_STREAM_THROTTLE(
5, "Unsupported IMU type ADUS16488.");
ROS_ERROR_STREAM_THROTTLE(5, "Unsupported IMU type ADUS16488.");
return false;
}
gyro_scale = param.gyro_scale * param.sampling_rate_hz;
......@@ -938,9 +940,7 @@ bool NovatelParser::handle_glo_eph(const novatel::GLO_Ephemeris* glo_emph) {
void NovatelParser::set_observation_time() {
int week = 0;
double second = 0.0;
second = time2gpst(_raw.time, &week);
double second = time2gpst(_raw.time, &week);
_gnss_observation.set_gnss_time_type(apollo::drivers::gnss::GPS_TIME);
_gnss_observation.set_gnss_week(week);
_gnss_observation.set_gnss_second_s(second);
......@@ -948,9 +948,8 @@ void NovatelParser::set_observation_time() {
bool NovatelParser::decode_gnss_observation(const uint8_t* obs_data,
const uint8_t* obs_data_end) {
int status = 0;
while (obs_data < obs_data_end) {
status = input_oem4(&_raw, *obs_data++);
const int status = input_oem4(&_raw, *obs_data++);
switch (status) {
case 1: // observation data
if (_raw.obs.n == 0) {
......
......@@ -41,7 +41,7 @@ constexpr bool is_zero(T value) {
class Rtcm3Parser : public Parser {
public:
Rtcm3Parser(bool is_base_satation);
explicit Rtcm3Parser(bool is_base_satation);
virtual MessageType get_message(MessagePtr &message_ptr);
private:
......@@ -168,9 +168,8 @@ void Rtcm3Parser::fill_glonass_orbit(
// orbit.set_tk(eph.tof.time + eph.tof.sec);
int week = 0;
double second = 0.0;
second = time2gpst(eph.toe, &week);
double second = time2gpst(eph.toe, &week);
orbit.set_week_num(week);
orbit.set_week_second_s(second);
orbit.set_toe(second);
......@@ -187,10 +186,7 @@ void Rtcm3Parser::fill_glonass_orbit(
void Rtcm3Parser::set_observation_time() {
int week = 0;
double second = 0.0;
second = time2gpst(_rtcm.time, &week);
double second = time2gpst(_rtcm.time, &week);
_observation.set_gnss_time_type(apollo::drivers::gnss::GPS_TIME);
_observation.set_gnss_week(week);
_observation.set_gnss_second_s(second);
......@@ -201,9 +197,8 @@ Parser::MessageType Rtcm3Parser::get_message(MessagePtr &message_ptr) {
return MessageType::NONE;
}
int status = 0;
while (_data < _data_end) {
status = input_rtcm3(&_rtcm, *_data++); // parse data use rtklib
const int status = input_rtcm3(&_rtcm, *_data++); // parse data use rtklib
switch (status) {
case 1: // observation data
......
......@@ -29,6 +29,8 @@ namespace velodyne {
// configuration parameters
struct Config {
Config()
: npackets(0), rpm(0.0), firing_data_port(0), positioning_data_port(0) {}
std::string frame_id; ///< tf frame ID
std::string model; ///< device model name
std::string topic;
......@@ -41,7 +43,7 @@ struct Config {
class VelodyneDriver {
public:
VelodyneDriver();
~VelodyneDriver() {}
virtual ~VelodyneDriver() {}
virtual bool poll(void) = 0;
virtual void init(ros::NodeHandle &node) = 0;
......@@ -63,8 +65,8 @@ class VelodyneDriver {
class Velodyne64Driver : public VelodyneDriver {
public:
Velodyne64Driver(Config config);
~Velodyne64Driver() {}
explicit Velodyne64Driver(const Config &config);
virtual ~Velodyne64Driver() {}
void init(ros::NodeHandle &node);
bool poll(void);
......@@ -74,8 +76,8 @@ class Velodyne64Driver : public VelodyneDriver {
class Velodyne16Driver : public VelodyneDriver {
public:
Velodyne16Driver(Config config);
~Velodyne16Driver() {}
explicit Velodyne16Driver(const Config &config);
virtual ~Velodyne16Driver() {}
void init(ros::NodeHandle &node);
bool poll(void);
......@@ -84,6 +86,7 @@ class Velodyne16Driver : public VelodyneDriver {
private:
boost::shared_ptr<Input> positioning_input_;
};
class VelodyneDriverFactory {
public:
static VelodyneDriver *create_driver(ros::NodeHandle private_nh);
......
......@@ -26,7 +26,7 @@ namespace apollo {
namespace drivers {
namespace velodyne {
Velodyne16Driver::Velodyne16Driver(Config config) : config_(config) {}
Velodyne16Driver::Velodyne16Driver(const Config &config) : config_(config) {}
void Velodyne16Driver::init(ros::NodeHandle &node) {
double packet_rate = 754; // packet frequency (Hz)
......
......@@ -25,11 +25,11 @@ namespace apollo {
namespace drivers {
namespace velodyne {
Velodyne64Driver::Velodyne64Driver(Config config) {
Velodyne64Driver::Velodyne64Driver(const Config& config) {
config_ = config;
}
void Velodyne64Driver::init(ros::NodeHandle &node) {
void Velodyne64Driver::init(ros::NodeHandle& node) {
double packet_rate = 0; // packet frequency (Hz)
if (config_.model == "64E_S2" || config_.model == "64E_S3S") {
packet_rate = 3472.17; // 1333312 / 384
......
......@@ -153,7 +153,7 @@ void operator>>(const YAML::Node& node, Calibration& calibration) {
}
YAML::Emitter& operator<<(YAML::Emitter& out,
const std::pair<int, LaserCorrection> correction) {
const std::pair<int, LaserCorrection>& correction) {
out << YAML::BeginMap;
out << YAML::Key << LASER_ID << YAML::Value << correction.first;
out << YAML::Key << ROT_CORRECTION << YAML::Value
......@@ -190,7 +190,7 @@ YAML::Emitter& operator<<(YAML::Emitter& out, const Calibration& calibration) {
for (std::map<int, LaserCorrection>::const_iterator it =
calibration.laser_corrections_.begin();
it != calibration.laser_corrections_.end(); it++) {
it != calibration.laser_corrections_.end(); ++it) {
out << *it;
}
......
......@@ -102,11 +102,14 @@ int OnlineCalibration::decode(
void OnlineCalibration::get_unit_index() {
int size = status_values_.size();
// simple check only for value, maybe need more check fro status tyep
// simple check only for value, maybe need more check fro status type
// TODO(velodyne driver developers): fix the following code logic
/*
int start_index = 0;
if (unit_indexs_.size() > 0) {
start_index = unit_indexs_.back() + 5;
}
*/
for (int start_index = 0; start_index < size - 5; ++start_index) {
if (status_values_[start_index] == 85 // "U"
&& status_values_[start_index + 1] == 78 // "N"
......@@ -149,4 +152,4 @@ void OnlineCalibration::dump(const std::string& file_path) {
} // namespace velodyne
} // namespace drivers
} // namespace apollo
\ No newline at end of file
} // namespace apollo
......@@ -66,7 +66,6 @@ double Velodyne16Parser::get_timestamp(double base_time, float time_offset,
*/
void Velodyne16Parser::unpack(const velodyne_msgs::VelodynePacket& pkt,
VPointCloud& pc) {
float azimuth = 0.0;
float azimuth_diff = 0.0;
float last_azimuth_diff = 0.0;
float azimuth_corrected_f = 0.0;
......@@ -76,7 +75,7 @@ void Velodyne16Parser::unpack(const velodyne_msgs::VelodynePacket& pkt,
double basetime = raw->gps_timestamp; // usec
for (int block = 0; block < BLOCKS_PER_PACKET; block++) {
azimuth = (float)(raw->blocks[block].rotation);
float azimuth = static_cast<float>(raw->blocks[block].rotation);
if (block < (BLOCKS_PER_PACKET - 1)) {
azimuth_diff = (float)((36000 + raw->blocks[block + 1].rotation -
raw->blocks[block].rotation) %
......
......@@ -149,7 +149,7 @@ void VelodyneParser::compute_coords(const union RawDistance &raw_distance,
sin_rot_table_[rotation] * corrections.cos_rot_correction -
cos_rot_table_[rotation] * corrections.sin_rot_correction;
double vert_offset = corrections.vert_offset_correction;
// double vert_offset = corrections.vert_offset_correction;
// Compute the distance in the xy plane (w/o accounting for rotation)
double xy_distance = distance * corrections.cos_vert_correction;
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册