Skip to content

Commit

Permalink
Robot: Code clean with clang-format.
Browse files Browse the repository at this point in the history
  • Loading branch information
xiaoxq authored and kechxu committed Sep 23, 2019
1 parent 13cdb58 commit f908589
Show file tree
Hide file tree
Showing 17 changed files with 57 additions and 80 deletions.
12 changes: 6 additions & 6 deletions cyber/base/bounded_queue.h
Original file line number Diff line number Diff line change
Expand Up @@ -120,9 +120,9 @@ bool BoundedQueue<T>::Enqueue(const T& element) {
pool_[GetIndex(old_tail)] = element;
do {
old_commit = old_tail;
} while (cyber_unlikely(!commit_.compare_exchange_weak(old_commit, new_tail,
std::memory_order_acq_rel,
std::memory_order_relaxed)));
} while (cyber_unlikely(!commit_.compare_exchange_weak(
old_commit, new_tail, std::memory_order_acq_rel,
std::memory_order_relaxed)));
wait_strategy_->NotifyOne();
return true;
}
Expand All @@ -143,9 +143,9 @@ bool BoundedQueue<T>::Enqueue(T&& element) {
pool_[GetIndex(old_tail)] = element;
do {
old_commit = old_tail;
} while (cyber_unlikely(!commit_.compare_exchange_weak(old_commit, new_tail,
std::memory_order_acq_rel,
std::memory_order_relaxed)));
} while (cyber_unlikely(!commit_.compare_exchange_weak(
old_commit, new_tail, std::memory_order_acq_rel,
std::memory_order_relaxed)));
wait_strategy_->NotifyOne();
return true;
}
Expand Down
32 changes: 8 additions & 24 deletions cyber/event/perf_event.h
Original file line number Diff line number Diff line change
Expand Up @@ -60,28 +60,14 @@ class EventBase {
void set_etype(int etype) { etype_ = etype; }
void set_stamp(uint64_t stamp) { stamp_ = stamp; }

virtual void set_cr_id(uint64_t cr_id) {
UNUSED(cr_id);
}
virtual void set_cr_state(int cr_state) {
UNUSED(cr_state);
}
virtual void set_proc_id(int proc_id) {
UNUSED(proc_id);
}
virtual void set_fetch_res(int fetch_res) {
UNUSED(fetch_res);
}
virtual void set_cr_id(uint64_t cr_id) { UNUSED(cr_id); }
virtual void set_cr_state(int cr_state) { UNUSED(cr_state); }
virtual void set_proc_id(int proc_id) { UNUSED(proc_id); }
virtual void set_fetch_res(int fetch_res) { UNUSED(fetch_res); }

virtual void set_msg_seq(uint64_t msg_seq) {
UNUSED(msg_seq);
}
virtual void set_channel_id(uint64_t channel_id) {
UNUSED(channel_id);
}
virtual void set_adder(const std::string& adder) {
UNUSED(adder);
}
virtual void set_msg_seq(uint64_t msg_seq) { UNUSED(msg_seq); }
virtual void set_channel_id(uint64_t channel_id) { UNUSED(channel_id); }
virtual void set_adder(const std::string& adder) { UNUSED(adder); }

protected:
int etype_;
Expand Down Expand Up @@ -141,9 +127,7 @@ class TransportEvent : public EventBase {
void set_channel_id(uint64_t channel_id) override {
channel_id_ = channel_id;
}
void set_adder(const std::string& adder) override {
adder_ = adder;
}
void set_adder(const std::string& adder) override { adder_ = adder; }

static std::string ShowTransPerf(TransPerf type) {
if (type == TransPerf::TRANSMIT_BEGIN) {
Expand Down
4 changes: 1 addition & 3 deletions cyber/event/perf_event_cache.cc
Original file line number Diff line number Diff line change
Expand Up @@ -47,9 +47,7 @@ PerfEventCache::PerfEventCache() {
}
}

PerfEventCache::~PerfEventCache() {
Shutdown();
}
PerfEventCache::~PerfEventCache() { Shutdown(); }

void PerfEventCache::Shutdown() {
if (!enable_) {
Expand Down
2 changes: 1 addition & 1 deletion cyber/init.cc
Original file line number Diff line number Diff line change
Expand Up @@ -30,10 +30,10 @@
#include "cyber/logger/async_logger.h"
#include "cyber/scheduler/scheduler.h"
#include "cyber/service_discovery/topology_manager.h"
#include "cyber/sysmo/sysmo.h"
#include "cyber/task/task.h"
#include "cyber/timer/timing_wheel.h"
#include "cyber/transport/transport.h"
#include "cyber/sysmo/sysmo.h"

namespace apollo {
namespace cyber {
Expand Down
2 changes: 1 addition & 1 deletion cyber/node/node_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ TEST(NodeTest, cases) {
auto writer = node->CreateWriter<Chatter>(attr);
auto server = node->CreateService<Chatter, Chatter>(
"node_test_server", [](const std::shared_ptr<Chatter>& request,
std::shared_ptr<Chatter>& response) {
std::shared_ptr<Chatter>& response) {
AINFO << "server: I am server";
static uint64_t id = 0;
++id;
Expand Down
5 changes: 2 additions & 3 deletions cyber/scheduler/common/pin_thread.cc
Original file line number Diff line number Diff line change
Expand Up @@ -49,8 +49,7 @@ void ParseCpuset(const std::string& str, std::vector<int>* cpuset) {
}
}

void SetSchedAffinity(std::thread* thread,
const std::vector<int>& cpus,
void SetSchedAffinity(std::thread* thread, const std::vector<int>& cpus,
const std::string& affinity, int cpu_id) {
cpu_set_t set;
CPU_ZERO(&set);
Expand Down Expand Up @@ -78,7 +77,7 @@ void SetSchedPolicy(std::thread* thread, std::string spolicy,
struct sched_param sp;
int policy;

memset(reinterpret_cast<void *>(&sp), 0, sizeof(sp));
memset(reinterpret_cast<void*>(&sp), 0, sizeof(sp));
sp.sched_priority = sched_priority;

if (!spolicy.compare("SCHED_FIFO")) {
Expand Down
14 changes: 5 additions & 9 deletions cyber/scheduler/common/pin_thread.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,15 +29,11 @@ namespace scheduler {

void ParseCpuset(const std::string& str, std::vector<int>* cpuset);

void SetSchedAffinity(std::thread* thread,
const std::vector<int>& cpus,
const std::string& affinity,
int cpu_id = -1);

void SetSchedPolicy(std::thread* thread,
std::string spolicy,
int sched_priority,
pid_t tid = -1);
void SetSchedAffinity(std::thread* thread, const std::vector<int>& cpus,
const std::string& affinity, int cpu_id = -1);

void SetSchedPolicy(std::thread* thread, std::string spolicy,
int sched_priority, pid_t tid = -1);

} // namespace scheduler
} // namespace cyber
Expand Down
5 changes: 2 additions & 3 deletions cyber/scheduler/common/pin_thread_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -77,9 +77,8 @@ TEST(pin_thread_test, sched_policy) {

policy = "SCHED_OTHER";
std::atomic<pid_t> tid{-1};
std::thread t2 = std::thread([&]() {
tid = static_cast<int>(syscall(SYS_gettid));
});
std::thread t2 =
std::thread([&]() { tid = static_cast<int>(syscall(SYS_gettid)); });
while (tid.load() == -1) {
cpu_relax();
}
Expand Down
4 changes: 2 additions & 2 deletions cyber/scheduler/policy/scheduler_choreography.cc
Original file line number Diff line number Diff line change
Expand Up @@ -112,8 +112,8 @@ void SchedulerChoreography::CreateProcessor() {

proc->BindContext(ctx);
SetSchedAffinity(proc->Thread(), pool_cpuset_, pool_affinity_, i);
SetSchedPolicy(proc->Thread(), pool_processor_policy_,
pool_processor_prio_, proc->Tid());
SetSchedPolicy(proc->Thread(), pool_processor_policy_, pool_processor_prio_,
proc->Tid());
pctxs_.emplace_back(ctx);
processors_.emplace_back(proc);
}
Expand Down
4 changes: 2 additions & 2 deletions cyber/scheduler/policy/scheduler_classic.cc
Original file line number Diff line number Diff line change
Expand Up @@ -102,8 +102,8 @@ void SchedulerClassic::CreateProcessor() {
auto proc = std::make_shared<Processor>();
proc->BindContext(ctx);
SetSchedAffinity(proc->Thread(), cpuset, affinity, i);
SetSchedPolicy(proc->Thread(), processor_policy,
processor_prio, proc->Tid());
SetSchedPolicy(proc->Thread(), processor_policy, processor_prio,
proc->Tid());
processors_.emplace_back(proc);
}
}
Expand Down
2 changes: 1 addition & 1 deletion cyber/scheduler/processor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ void Processor::Stop() {
}
}

void Processor::BindContext(const std::shared_ptr<ProcessorContext> &context) {
void Processor::BindContext(const std::shared_ptr<ProcessorContext>& context) {
context_ = context;
std::call_once(thread_flag_,
[this]() { thread_ = std::thread(&Processor::Run, this); });
Expand Down
2 changes: 1 addition & 1 deletion cyber/scheduler/processor_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,8 @@ namespace apollo {
namespace cyber {
namespace scheduler {

using scheduler::Processor;
using scheduler::ChoreographyContext;
using scheduler::Processor;

TEST(ProcessorTest, all) {
auto proc = std::make_shared<Processor>();
Expand Down
8 changes: 5 additions & 3 deletions cyber/scheduler/scheduler.cc
Original file line number Diff line number Diff line change
Expand Up @@ -106,11 +106,13 @@ void Scheduler::CheckSchedStatus() {
if (snap->execute_start_time.load()) {
auto execute_time = (now - snap->execute_start_time.load()) / 1000000;
snap_info.append(std::to_string(snap->processor_id.load()))
.append(":").append(snap->routine_name)
.append(":").append(std::to_string(execute_time));
.append(":")
.append(snap->routine_name)
.append(":")
.append(std::to_string(execute_time));
} else {
snap_info.append(std::to_string(snap->processor_id.load()))
.append(":idle");
.append(":idle");
}
snap_info.append(", ");
}
Expand Down
16 changes: 8 additions & 8 deletions modules/perception/camera/app/obstacle_camera_perception.cc
Original file line number Diff line number Diff line change
Expand Up @@ -319,27 +319,27 @@ bool ObstacleCameraPerception::Perception(
AERROR << "Failed to detect lane.";
return false;
}
PERCEPTION_PERF_BLOCK_END_WITH_INDICATOR(
frame->data_provider->sensor_name(), "LaneDetector");
PERCEPTION_PERF_BLOCK_END_WITH_INDICATOR(frame->data_provider->sensor_name(),
"LaneDetector");

if (!lane_postprocessor_->Process2D(lane_postprocessor_options, frame)) {
AERROR << "Failed to postprocess lane 2D.";
return false;
}
PERCEPTION_PERF_BLOCK_END_WITH_INDICATOR(
frame->data_provider->sensor_name(), "LanePostprocessor2D");
PERCEPTION_PERF_BLOCK_END_WITH_INDICATOR(frame->data_provider->sensor_name(),
"LanePostprocessor2D");

// Calibration service
frame->calibration_service->Update(frame);
PERCEPTION_PERF_BLOCK_END_WITH_INDICATOR(
frame->data_provider->sensor_name(), "CalibrationService");
PERCEPTION_PERF_BLOCK_END_WITH_INDICATOR(frame->data_provider->sensor_name(),
"CalibrationService");

if (!lane_postprocessor_->Process3D(lane_postprocessor_options, frame)) {
AERROR << "Failed to postprocess lane 3D.";
return false;
}
PERCEPTION_PERF_BLOCK_END_WITH_INDICATOR(
frame->data_provider->sensor_name(), "LanePostprocessor3D");
PERCEPTION_PERF_BLOCK_END_WITH_INDICATOR(frame->data_provider->sensor_name(),
"LanePostprocessor3D");

if (write_out_lane_file_) {
std::string lane_file_path =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -186,7 +186,7 @@ TEST(darkSCNNLanePostprocessor, camera_lane_postprocessor_point_test) {

intrinsic_map["onsemi_obstacle"] = frame.camera_k_matrix;
extrinsic_map["onsemi_obstacle"] = ex_camera2lidar;
std::vector <std::string> camera_names;
std::vector<std::string> camera_names;
camera_names[0] = visual_camera;

EXPECT_TRUE(visualize_.Init_all_info_single_camera(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -800,17 +800,16 @@ int FusionCameraDetectionComponent::InternalProc(
*error_code));
bool send_viz_ret = camera_viz_writer_->Write(viz_msg);
AINFO << "send out camera visualization msg, ts: "
<< std::to_string(msg_timestamp)
<< " send_viz_ret: " << send_viz_ret;
<< std::to_string(msg_timestamp) << " send_viz_ret: " << send_viz_ret;

cv::Mat output_image(image_height_, image_width_, CV_8UC3,
cv::Scalar(0, 0, 0));
base::Image8U out_image(image_height_, image_width_, base::Color::RGB);
camera_frame.data_provider->GetImage(image_options, &out_image);
memcpy(output_image.data, out_image.cpu_data(),
out_image.total() * sizeof(uint8_t));
visualize_.ShowResult_all_info_single_camera(
output_image, camera_frame, motion_buffer_, world2camera);
visualize_.ShowResult_all_info_single_camera(output_image, camera_frame,
motion_buffer_, world2camera);
}

// send out camera debug message
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -136,8 +136,8 @@ Status PathBoundsDecider::Process(
if (FLAGS_enable_smarter_lane_change &&
reference_line_info->IsChangeLanePath()) {
PathBound lanechange_path_bound;
Status ret = GenerateLaneChangePathBound(
*reference_line_info, &lanechange_path_bound);
Status ret = GenerateLaneChangePathBound(*reference_line_info,
&lanechange_path_bound);
if (!ret.ok()) {
ADEBUG << "Cannot generate a lane-change path bound.";
return Status(ErrorCode::PLANNING_ERROR, ret.error_message());
Expand All @@ -157,8 +157,8 @@ Status PathBoundsDecider::Process(
std::get<2>(lanechange_path_bound[i]));
}
candidate_path_boundaries.emplace_back(
std::get<0>(lanechange_path_bound[0]),
kPathBoundsDeciderResolution, lanechange_path_bound_pair);
std::get<0>(lanechange_path_bound[0]), kPathBoundsDeciderResolution,
lanechange_path_bound_pair);
candidate_path_boundaries.back().set_label("regular/lanechange");
RecordDebugInfo(lanechange_path_bound, "", reference_line_info);
reference_line_info->SetCandidatePathBoundaries(
Expand Down Expand Up @@ -1139,14 +1139,14 @@ void PathBoundsDecider::GetBoundaryFromLaneChangeForbiddenZone(
adc_frenet_l_ > curr_lane_left_width
? curr_lane_left_width + GetBufferBetweenADCCenterAndEdge()
: std::get<1>((*path_bound)[i]);
std::get<1>((*path_bound)[i]) = std::fmin(
std::get<1>((*path_bound)[i]), adc_frenet_l_ - 0.1);
std::get<1>((*path_bound)[i]) =
std::fmin(std::get<1>((*path_bound)[i]), adc_frenet_l_ - 0.1);
std::get<2>((*path_bound)[i]) =
adc_frenet_l_ < -curr_lane_right_width
? -curr_lane_right_width - GetBufferBetweenADCCenterAndEdge()
: std::get<2>((*path_bound)[i]);
std::get<2>((*path_bound)[i]) = std::fmax(
std::get<2>((*path_bound)[i]), adc_frenet_l_ + 0.1);
std::get<2>((*path_bound)[i]) =
std::fmax(std::get<2>((*path_bound)[i]), adc_frenet_l_ + 0.1);
}
}

Expand Down

0 comments on commit f908589

Please sign in to comment.