Skip to content

Commit

Permalink
All: fixed safety bugs.
Browse files Browse the repository at this point in the history
  • Loading branch information
lianglia-apollo authored and ycool committed Dec 21, 2018
1 parent b4aa20c commit bdedf08
Show file tree
Hide file tree
Showing 10 changed files with 75 additions and 78 deletions.
2 changes: 1 addition & 1 deletion cyber/scheduler/scheduler.cc
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,7 @@ void Scheduler::ParseCpuset(const std::string& str, std::vector<int>* cpuset) {

for (std::vector<std::string>::const_iterator it = lines.begin(),
e = lines.end();
it != e; it++) {
it != e; ++it) {
std::stringstream ss(*it);
std::vector<std::string> range;

Expand Down
33 changes: 16 additions & 17 deletions modules/perception/fusion/common/camera_util.cc
Original file line number Diff line number Diff line change
Expand Up @@ -55,22 +55,21 @@ bool Pt3dToCamera2d(const Eigen::Vector3d& pt3d,
const Eigen::Matrix4d& world2camera_pose,
base::BaseCameraModelPtr camera_model,
Eigen::Vector2d* pt2d) {
Eigen::Vector4d local_pt =
static_cast<Eigen::Matrix<double, 4, 1, 0, 4, 1>>
(world2camera_pose * Eigen::Vector4d(pt3d(0), pt3d(1), pt3d(2), 1));
Eigen::Vector4d local_pt = static_cast<Eigen::Matrix<double, 4, 1, 0, 4, 1>>(
world2camera_pose * Eigen::Vector4d(pt3d(0), pt3d(1), pt3d(2), 1));
if (local_pt[2] > 0) {
*pt2d = (camera_model->Project(
Eigen::Vector3f(static_cast<float>(local_pt[0]),
static_cast<float>(local_pt[1]),
static_cast<float>(local_pt[2]))))
.cast<double>();
*pt2d =
(camera_model->Project(Eigen::Vector3f(
static_cast<float>(local_pt[0]), static_cast<float>(local_pt[1]),
static_cast<float>(local_pt[2]))))
.cast<double>();
return true;
}
return false;
}

bool IsObjectEightVerticesAllBehindCamera(
std::shared_ptr<const base::Object> obj,
const std::shared_ptr<const base::Object>& obj,
const Eigen::Matrix4d& world2camera_pose,
base::BaseCameraModelPtr camera_model) {
std::vector<Eigen::Vector3d> vertices(8);
Expand Down Expand Up @@ -100,8 +99,8 @@ float ObjectInCameraView(SensorObjectConstPtr sensor_object,

double time_diff =
camera_ts - sensor_object->GetBaseObject()->latest_tracked_time;
Eigen::Vector3f offset = sensor_object->GetBaseObject()->velocity *
static_cast<float>(time_diff);
Eigen::Vector3f offset =
sensor_object->GetBaseObject()->velocity * static_cast<float>(time_diff);
if (!motion_compensation) {
offset.setZero();
}
Expand Down Expand Up @@ -165,8 +164,8 @@ float ObjectInCameraView(SensorObjectConstPtr sensor_object,
bottom_right.cwiseMin(Eigen::Vector2d(width, height));
Eigen::Vector2d bound_box_size = bound_bottom_right - bound_top_left;
if ((bound_box_size.array() > 0.0).all()) {
in_view_ratio = static_cast<float>(bound_box_size.prod() /
box_size.prod());
in_view_ratio =
static_cast<float>(bound_box_size.prod() / box_size.prod());
} else {
in_view_ratio = 0.0;
}
Expand All @@ -191,13 +190,13 @@ float ObjectInCameraView(SensorObjectConstPtr sensor_object,
const double dist_slope = 0.25;
auto sigmoid_like_fun = [max_dist, dist_slope](double obj_dist) {
double x = obj_dist - max_dist;
return 0.5 - 0.5 * x * dist_slope /
std::sqrt(1 + x * x * dist_slope * dist_slope);
return 0.5 -
0.5 * x * dist_slope /
std::sqrt(1 + x * x * dist_slope * dist_slope);
};
Eigen::Vector4d center3d_local = world2sensor_pose * center.homogeneous();
double dist_to_camera = center3d_local.z();
return static_cast<float>(in_view_ratio *
sigmoid_like_fun(dist_to_camera));
return static_cast<float>(in_view_ratio * sigmoid_like_fun(dist_to_camera));
}

} // namespace fusion
Expand Down
2 changes: 1 addition & 1 deletion modules/perception/fusion/common/camera_util.h
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ bool Pt3dToCamera2d(const Eigen::Vector3d& pt3d,
// @param [in]: world2camera_pose
// @param [in]: camera_model
bool IsObjectEightVerticesAllBehindCamera(
std::shared_ptr<const base::Object> obj,
const std::shared_ptr<const base::Object>& obj,
const Eigen::Matrix4d& world2camera_pose,
base::BaseCameraModelPtr camera_model);

Expand Down
2 changes: 1 addition & 1 deletion modules/perception/lidar/common/lidar_object_util.cc
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ using base::PointF;
using base::PointD;
using base::PointCloud;

void GetBoundingBox2d(const std::shared_ptr<Object> object,
void GetBoundingBox2d(const std::shared_ptr<Object>& object,
PointCloud<PointD>* box, double expand) {
box->clear();
box->resize(4);
Expand Down
2 changes: 1 addition & 1 deletion modules/perception/lidar/common/lidar_object_util.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ namespace lidar {
// @param [in]: object
// @param [in]: expand valud, in meter
// @param [out]: bounding box vertices(4 in xy plane)
void GetBoundingBox2d(const std::shared_ptr<base::Object> object,
void GetBoundingBox2d(const std::shared_ptr<base::Object>& object,
base::PointCloud<base::PointD>* box, double expand = 0.0);

// @brief: compute object shape(center, size) from given direction and polygon
Expand Down
2 changes: 1 addition & 1 deletion modules/planning/open_space/open_space_roi_wrapper.cc
Original file line number Diff line number Diff line change
Expand Up @@ -402,11 +402,11 @@ class OpenSpaceROITest {
hdmap::Id target_lane_id;
target_lane_id.set_id(parking_id);
auto nearby_lane = map_ptr->GetLaneById(nearby_lane_id);
std::cout << "the lane found is " << nearby_lane->id().id() << std::endl;
if (nearby_lane == nullptr) {
std::cout << "No such lane found " << lane_id << std::endl;
return false;
}
std::cout << "the lane found is " << nearby_lane->id().id() << std::endl;
LaneSegment nearby_lanesegment =
LaneSegment(nearby_lane, nearby_lane->accumulate_s().front(),
nearby_lane->accumulate_s().back());
Expand Down
3 changes: 2 additions & 1 deletion modules/planning/planner/public_road/public_road_planner.cc
Original file line number Diff line number Diff line change
Expand Up @@ -44,12 +44,13 @@ Status PublicRoadPlanner::Init(const PlanningConfig& config) {

Status PublicRoadPlanner::Plan(const TrajectoryPoint& planning_start_point,
Frame* frame) {
DCHECK_NOTNULL(frame);
scenario_manager_.Update(planning_start_point, *frame);
scenario_ = scenario_manager_.mutable_scenario();
auto result = scenario_->Process(planning_start_point, frame);

if (FLAGS_enable_record_debug) {
if (frame && frame->output_trajectory()) {
if (frame->output_trajectory()) {
auto scenario_debug = frame->output_trajectory()
->mutable_debug()
->mutable_planning_data()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,16 @@ PolyVTSpeedOptimizer::PolyVTSpeedOptimizer(const TaskConfig& config)

apollo::common::Status PolyVTSpeedOptimizer::Execute(
Frame* frame, ReferenceLineInfo* reference_line_info) {
if (frame == nullptr) {
AERROR << "Frame info is empty!";
return Status(ErrorCode::PLANNING_ERROR, "No Frame info");
}

if (reference_line_info == nullptr) {
AERROR << "Reference line info is empty!";
return Status(ErrorCode::PLANNING_ERROR, "No reference line info!");
}

const auto& poly_vt_config = config_.poly_vt_speed_config();
// extract infos
const SLBoundary& adc_sl_boundary = reference_line_info->AdcSlBoundary();
Expand All @@ -64,21 +74,11 @@ apollo::common::Status PolyVTSpeedOptimizer::Execute(
PathDecision* path_decision = reference_line_info->path_decision();
SpeedData* speed_data = reference_line_info->mutable_speed_data();

if (reference_line_info == nullptr) {
AERROR << "Reference line info is empty!";
return Status(ErrorCode::PLANNING_ERROR, "No reference line info!");
}

reference_line_info_ = reference_line_info;
if (reference_line_info->ReachedDestination()) {
return Status::OK();
}

if (frame == nullptr) {
AERROR << "Frame info is empty!";
return Status(ErrorCode::PLANNING_ERROR, "No Frame info");
}

if (path_data.discretized_path().empty()) {
std::string msg("Empty path data");
AERROR << msg;
Expand Down
10 changes: 5 additions & 5 deletions modules/tools/visualizer/radarpoints.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,8 @@

#include <iostream>

RadarPoints::RadarPoints(std::shared_ptr<QOpenGLShaderProgram> shaderProgram)
RadarPoints::RadarPoints(
const std::shared_ptr<QOpenGLShaderProgram>& shaderProgram)
: RenderableObject(1, 3, shaderProgram),
color_(1.0f, 0.0f, 0.0f),
buffer_(nullptr) {}
Expand All @@ -35,10 +36,9 @@ bool RadarPoints::FillData(
const ::google::protobuf::Map<::google::protobuf::int32,
apollo::drivers::RadarObstacle>&
radarObstacles = rawData->radar_obstacle();
for (::google::protobuf::Map<
::google::protobuf::int32,
apollo::drivers::RadarObstacle>::const_iterator iter =
radarObstacles.cbegin();
for (::google::protobuf::Map<::google::protobuf::int32,
apollo::drivers::RadarObstacle>::const_iterator
iter = radarObstacles.cbegin();
iter != radarObstacles.cend(); ++iter, ptr += vertex_element_count()) {
const apollo::common::Point2D& position =
iter->second.absolute_position();
Expand Down
77 changes: 37 additions & 40 deletions modules/tools/visualizer/radarpoints.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,54 +25,51 @@

class QOpenGLShaderProgram;

class RadarPoints : public RenderableObject
{
/* struct Point{
* GLfloat x, // raw data from radar
* GLfloat y,
* GLfloat r
* };
*/

public:
explicit RadarPoints(std::shared_ptr<QOpenGLShaderProgram> shaderProgram = nullptr);
~RadarPoints(void){
if(buffer_){
delete [] buffer_;
buffer_ = nullptr;
}
class RadarPoints : public RenderableObject {
/* struct Point{
* GLfloat x, // raw data from radar
* GLfloat y,
* GLfloat r
* };
*/

public:
explicit RadarPoints(
const std::shared_ptr<QOpenGLShaderProgram>& shaderProgram = nullptr);
~RadarPoints(void) {
if (buffer_) {
delete[] buffer_;
buffer_ = nullptr;
}
}

virtual GLenum GetPrimitiveType(void) const { return GL_POINTS; }
virtual GLenum GetPrimitiveType(void) const { return GL_POINTS; }

void SetupExtraUniforms(void) {
shader_program_->setUniformValue("color", color_);
}
void SetupExtraUniforms(void) {
shader_program_->setUniformValue("color", color_);
}

GLfloat red(void) const { return color_.x(); }
GLfloat green(void) const { return color_.y(); }
GLfloat blue(void) const { return color_.z(); }
GLfloat red(void) const { return color_.x(); }
GLfloat green(void) const { return color_.y(); }
GLfloat blue(void) const { return color_.z(); }

const QVector3D& color(void) const { return color_; }
const QVector3D& color(void) const { return color_; }

void set_color(const QRgb& rgb){
set_color(QColor(rgb));
}

void set_color(const QColor& color) {
color_.setX(static_cast<float>(color.redF()));
color_.setY(static_cast<float>(color.greenF()));
color_.setZ(static_cast<float>(color.blueF()));
}
void set_color(const QRgb& rgb) { set_color(QColor(rgb)); }

bool FillData(
const std::shared_ptr<const apollo::drivers::RadarObstacles>& pData);
void set_color(const QColor& color) {
color_.setX(static_cast<float>(color.redF()));
color_.setY(static_cast<float>(color.greenF()));
color_.setZ(static_cast<float>(color.blueF()));
}

protected:
bool FillVertexBuffer(GLfloat* pBuffer) override;
bool FillData(
const std::shared_ptr<const apollo::drivers::RadarObstacles>& pData);

private:
protected:
bool FillVertexBuffer(GLfloat* pBuffer) override;

QVector3D color_; // r, g, b
GLfloat* buffer_;
private:
QVector3D color_; // r, g, b
GLfloat* buffer_;
};

0 comments on commit bdedf08

Please sign in to comment.