diff --git a/.gitignore b/.gitignore index a771a956950..0d01b842f10 100644 --- a/.gitignore +++ b/.gitignore @@ -89,5 +89,5 @@ modules/calibration/data/ # Data bag docs/demo_guide/*.bag -# Cybertron -cybertron/log/* +# Logs +cyber/log/* diff --git a/apollo.sh b/apollo.sh index 91f1265ca8a..cb6c752988f 100755 --- a/apollo.sh +++ b/apollo.sh @@ -93,10 +93,10 @@ function check_esd_files() { function generate_build_targets() { if [ -z $NOT_BUILD_PERCEPTION ] ; then - BUILD_TARGETS=`bazel query //modules/... union //cybertron/...` + BUILD_TARGETS=`bazel query //modules/... union //cyber/...` else info 'Skip building perception module!' - BUILD_TARGETS=`bazel query //modules/... except //modules/perception/... except //modules/calibration/lidar_ex_checker/... union //cybertron/...` + BUILD_TARGETS=`bazel query //modules/... except //modules/perception/... except //modules/calibration/lidar_ex_checker/... union //cyber/...` fi if [ $? -ne 0 ]; then @@ -175,7 +175,7 @@ function cibuild_extended() { info "Building with $JOB_ARG for $MACHINE_ARCH" BUILD_TARGETS=" //modules/perception/... - //cybertron/... + //cyber/... //modules/dreamview/... //modules/drivers/radar/conti_radar/... //modules/drivers/radar/racobit_radar/... @@ -210,7 +210,7 @@ function cibuild() { info "Building with $JOB_ARG for $MACHINE_ARCH" BUILD_TARGETS=" - //cybertron/... + //cyber/... //modules/canbus/... //modules/common/... //modules/control/... @@ -412,10 +412,10 @@ function citest_basic() { info "Building framework ..." cd /apollo - source cybertron/setup.bash + source cyber/setup.bash BUILD_TARGETS=" - `bazel query //modules/... union //cybertron/...` + `bazel query //modules/... union //cyber/...` " JOB_ARG="--jobs=$(nproc) --ram_utilization_factor 80" @@ -447,10 +447,10 @@ function citest_extended() { info "Building framework ..." cd /apollo - source cybertron/setup.bash + source cyber/setup.bash BUILD_TARGETS=" - `bazel query //modules/planning/... union //modules/common/... union //cybertron/...` + `bazel query //modules/planning/... union //modules/common/... union //cyber/...` `bazel query //modules/prediction/... union //modules/control/...` " @@ -472,7 +472,7 @@ function citest_extended() { function citest() { info "Building framework ..." cd /apollo - source cybertron/setup.bash + source cyber/setup.bash citest_basic citest_extended @@ -500,7 +500,7 @@ function run_bash_lint() { function run_lint() { # Add cpplint rule to BUILD files that do not contain it. - for file in $(find cybertron modules -name BUILD | grep -v gnss/third_party | \ + for file in $(find cyber modules -name BUILD | grep -v gnss/third_party | \ xargs grep -l -E 'cc_library|cc_test|cc_binary' | xargs grep -L 'cpplint()') do sed -i '1i\load("//tools:cpplint.bzl", "cpplint")\n' $file diff --git a/cyber/BUILD b/cyber/BUILD new file mode 100644 index 00000000000..646b411f40a --- /dev/null +++ b/cyber/BUILD @@ -0,0 +1,126 @@ +load("//tools:cpplint.bzl", "cpplint") + +package(default_visibility = ["//visibility:public"]) + +cc_library( + name = "cyber", + deps = [ + "//cyber:cyber_core", + ], + linkstatic = False, +) + +cc_binary( + name = "mainboard", + srcs = glob([ + "mainboard/*.cc", + "mainboard/*.h", + ]), + deps = [ + ":cyber_core", + "//cyber/proto:dag_config_cc_proto", + ], + copts = [ + "-pthread", + ], + linkstatic = False, +) + +cc_binary( + name = "libcyber.so", + deps = [ + ":cyber_core", + "@fastrtps//:fastrtps", + ], + #TODO: Using deps instead. + linkopts = [ + "-luuid", + ], + linkshared = True, + linkstatic = True, +) + +cc_library( + name = "binary", + hdrs = [ + "binary.h", + ], +) + +cc_library( + name = "state", + srcs = [ + "state.cc", + ], + hdrs = [ + "state.h", + ], +) + +cc_library( + name = "init", + hdrs = [ + "cyber.h", + "init.h", + ], + deps = [ + "state", + ], +) + +cc_library( + name = "cyber_core", + srcs = [ + "cyber.cc", + "init.cc", + ], + deps = [ + "//cyber:binary", + "//cyber:state", + "//cyber/base", + "//cyber/blocker:blocker_manager", + "//cyber/common", + "//cyber/component:component", + "//cyber/component:timer_component", + "//cyber/class_loader:class_loader", + "//cyber/class_loader:class_loader_manager", + "//cyber/croutine:croutine", + "//cyber/data:data", + "//cyber/event:perf_event", + "//cyber/event:perf_event_cache", + "//cyber:init", + "//cyber/logger:logger", + "//cyber/logger:async_logger", + "//cyber/message:message_traits", + "//cyber/message:raw_message_traits", + "//cyber/message:py_message_traits", + "//cyber/message:protobuf_traits", + "//cyber/message:intra_message_traits", + "//cyber/node:node", + "//cyber/proto:run_mode_conf_cc_proto", + "//cyber/parameter:parameter_client", + "//cyber/parameter:parameter_server", + "//cyber/record:record", + "//cyber/scheduler:scheduler", + "//cyber/service:client", + "//cyber/service:service", + "//cyber/service_discovery:topology_manager", + "//cyber/task:task", + "//cyber/time:time", + "//cyber/time:duration", + "//cyber/time:rate", + "//cyber/timer:timer", + "//cyber/transport:transport_lib", + "//third_party/tf2:tf2", + "@fastrtps", + ], + linkopts = [ + "-luuid", + "-lprotobuf", + "-lglog", + "-lgflags", + ], +) + + +cpplint() diff --git a/cyber/README.md b/cyber/README.md new file mode 100644 index 00000000000..40fc9f2dac5 --- /dev/null +++ b/cyber/README.md @@ -0,0 +1,2 @@ +# Introduction + Cyber is a collection of software frameworks for self-driving application development, providing operating system-like functionality on a heterogeneous computer. This allows you to build, test, and deploy self-driving applications more efficient. diff --git a/cybertron/base/BUILD b/cyber/base/BUILD similarity index 70% rename from cybertron/base/BUILD rename to cyber/base/BUILD index df49dde5de1..ae6f81479ff 100644 --- a/cybertron/base/BUILD +++ b/cyber/base/BUILD @@ -5,21 +5,21 @@ package(default_visibility = ["//visibility:public"]) cc_library( name = "base", deps = [ - "//cybertron/base:any", - "//cybertron/base:atomic_fifo", - "//cybertron/base:atomic_hash_map", - "//cybertron/base:atomic_rw_lock", - "//cybertron/base:bounded_queue", - "//cybertron/base:concurrent_object_pool", - "//cybertron/base:macros", - "//cybertron/base:object_pool", - "//cybertron/base:reentrant_rw_lock", - "//cybertron/base:rw_lock_guard", - "//cybertron/base:signal", - "//cybertron/base:thread_pool", - "//cybertron/base:thread_safe_queue", - "//cybertron/base:unbounded_queue", - "//cybertron/base:wait_strategy", + "//cyber/base:any", + "//cyber/base:atomic_fifo", + "//cyber/base:atomic_hash_map", + "//cyber/base:atomic_rw_lock", + "//cyber/base:bounded_queue", + "//cyber/base:concurrent_object_pool", + "//cyber/base:macros", + "//cyber/base:object_pool", + "//cyber/base:reentrant_rw_lock", + "//cyber/base:rw_lock_guard", + "//cyber/base:signal", + "//cyber/base:thread_pool", + "//cyber/base:thread_safe_queue", + "//cyber/base:unbounded_queue", + "//cyber/base:wait_strategy", ], ) @@ -37,7 +37,7 @@ cc_test( "any_test.cc", ], deps = [ - "//cybertron/base:any", + "//cyber/base:any", "@gtest//:main", ], ) @@ -63,7 +63,7 @@ cc_test( "atomic_hash_map_test.cc", ], deps = [ - "//cybertron/base:atomic_hash_map", + "//cyber/base:atomic_hash_map", "@gtest//:main", ], ) @@ -75,7 +75,7 @@ cc_library( "atomic_rw_lock.h", ], deps = [ - "//cybertron/base:rw_lock_guard", + "//cyber/base:rw_lock_guard", ] ) @@ -86,8 +86,8 @@ cc_test( "atomic_rw_lock_test.cc", ], deps = [ - "//cybertron/base:atomic_rw_lock", - "//cybertron/base:reentrant_rw_lock", + "//cyber/base:atomic_rw_lock", + "//cyber/base:reentrant_rw_lock", "@gtest//:main", ], ) @@ -98,8 +98,8 @@ cc_library( "bounded_queue.h", ], deps = [ - "//cybertron/base:macros", - "//cybertron/base:wait_strategy", + "//cyber/base:macros", + "//cyber/base:wait_strategy", ], ) @@ -110,7 +110,7 @@ cc_test( "bounded_queue_test.cc", ], deps = [ - "//cybertron/base:bounded_queue", + "//cyber/base:bounded_queue", "@gtest//:main", ], ) @@ -135,7 +135,7 @@ cc_library( "object_pool.h", ], deps = [ - "//cybertron/base:macros", + "//cyber/base:macros", ], ) @@ -146,7 +146,7 @@ cc_test( "object_pool_test.cc", ], deps = [ - "//cybertron/base:object_pool", + "//cyber/base:object_pool", "@gtest//:main", ], ) @@ -179,7 +179,7 @@ cc_test( "signal_test.cc", ], deps = [ - "//cybertron/base:signal", + "//cyber/base:signal", "@gtest//:main", ], ) diff --git a/cybertron/base/any.h b/cyber/base/any.h similarity index 97% rename from cybertron/base/any.h rename to cyber/base/any.h index f2c447765d1..a3c47f56a9e 100644 --- a/cybertron/base/any.h +++ b/cyber/base/any.h @@ -14,15 +14,15 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_BASE_ANY_H_ -#define CYBERTRON_BASE_ANY_H_ +#ifndef CYBER_BASE_ANY_H_ +#define CYBER_BASE_ANY_H_ #include #include #include namespace apollo { -namespace cybertron { +namespace cyber { namespace data { class BadAnyCast : public std::bad_cast { @@ -215,7 +215,7 @@ inline ValueType AnyCast(const Any& operand) { } } // namespace data -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_BASE_ANY_H_ +#endif // CYBER_BASE_ANY_H_ diff --git a/cybertron/base/any_test.cc b/cyber/base/any_test.cc similarity index 97% rename from cybertron/base/any_test.cc rename to cyber/base/any_test.cc index c95c92fe12d..40560ed73e0 100644 --- a/cybertron/base/any_test.cc +++ b/cyber/base/any_test.cc @@ -19,11 +19,11 @@ #include #include -#include "cybertron/base/any.h" +#include "cyber/base/any.h" #include "gtest/gtest.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace data { class Foo { public: @@ -124,5 +124,5 @@ TEST(AnyTest, cast_test) { } } // namespace data -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/base/atomic_fifo.h b/cyber/base/atomic_fifo.h similarity index 94% rename from cybertron/base/atomic_fifo.h rename to cyber/base/atomic_fifo.h index 7ef7219e870..53ef7f48bd2 100755 --- a/cybertron/base/atomic_fifo.h +++ b/cyber/base/atomic_fifo.h @@ -14,18 +14,18 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_BASE_ATOMIC_FIFO_H_ -#define CYBERTRON_BASE_ATOMIC_FIFO_H_ +#ifndef CYBER_BASE_ATOMIC_FIFO_H_ +#define CYBER_BASE_ATOMIC_FIFO_H_ #include #include #include #include -#include "cybertron/base/macros.h" +#include "cyber/base/macros.h" namespace apollo { -namespace cybertron { +namespace cyber { template class AtomicFIFO { @@ -122,7 +122,7 @@ bool AtomicFIFO::Pop(T *value) { return true; } -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_BASE_ATOMIC_FIFO_H_ +#endif // CYBER_BASE_ATOMIC_FIFO_H_ diff --git a/cybertron/base/atomic_hash_map.h b/cyber/base/atomic_hash_map.h similarity index 98% rename from cybertron/base/atomic_hash_map.h rename to cyber/base/atomic_hash_map.h index eb86d59e5cf..3d3425941ba 100644 --- a/cybertron/base/atomic_hash_map.h +++ b/cyber/base/atomic_hash_map.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_BASE_ATOMIC_HASH_MAP_H_ -#define CYBERTRON_BASE_ATOMIC_HASH_MAP_H_ +#ifndef CYBER_BASE_ATOMIC_HASH_MAP_H_ +#define CYBER_BASE_ATOMIC_HASH_MAP_H_ #include #include @@ -23,7 +23,7 @@ #include namespace apollo { -namespace cybertron { +namespace cyber { namespace base { /** * @brief A implementation of lock-free fixed size hash map @@ -324,7 +324,7 @@ class AtomicHashMap { }; } // namespace base -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_BASE_ATOMIC_HASH_MAP_H_ +#endif // CYBER_BASE_ATOMIC_HASH_MAP_H_ diff --git a/cybertron/base/atomic_hash_map_test.cc b/cyber/base/atomic_hash_map_test.cc similarity index 95% rename from cybertron/base/atomic_hash_map_test.cc rename to cyber/base/atomic_hash_map_test.cc index e67cfa5e50e..f862fde93e1 100644 --- a/cybertron/base/atomic_hash_map_test.cc +++ b/cyber/base/atomic_hash_map_test.cc @@ -14,13 +14,13 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/base/atomic_hash_map.h" +#include "cyber/base/atomic_hash_map.h" #include #include #include "gtest/gtest.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace base { TEST(AtomicHashMapTest, int_int) { @@ -67,5 +67,5 @@ TEST(AtomicHashMapTest, int_str) { TEST(AtomicHashMapTest, concurrency) {} } // namespace base -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/base/atomic_rw_lock.h b/cyber/base/atomic_rw_lock.h similarity index 94% rename from cybertron/base/atomic_rw_lock.h rename to cyber/base/atomic_rw_lock.h index 99f06e077cb..a1b04eee16e 100644 --- a/cybertron/base/atomic_rw_lock.h +++ b/cyber/base/atomic_rw_lock.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_BASE_ATOMIC_RW_LOCK_H_ -#define CYBERTRON_BASE_ATOMIC_RW_LOCK_H_ +#ifndef CYBER_BASE_ATOMIC_RW_LOCK_H_ +#define CYBER_BASE_ATOMIC_RW_LOCK_H_ #include #include @@ -25,10 +25,10 @@ #include #include #include -#include "cybertron/base/rw_lock_guard.h" +#include "cyber/base/rw_lock_guard.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace base { class AtomicRWLock { @@ -112,7 +112,7 @@ inline void AtomicRWLock::ReadUnlock() { lock_num_.fetch_sub(1); } inline void AtomicRWLock::WriteUnlock() { lock_num_.fetch_add(1); } } // namespace base -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_BASE_ATOMIC_RW_LOCK_H_ +#endif // CYBER_BASE_ATOMIC_RW_LOCK_H_ diff --git a/cybertron/base/atomic_rw_lock_test.cc b/cyber/base/atomic_rw_lock_test.cc similarity index 94% rename from cybertron/base/atomic_rw_lock_test.cc rename to cyber/base/atomic_rw_lock_test.cc index bc8f2f494f3..bb14da17184 100644 --- a/cybertron/base/atomic_rw_lock_test.cc +++ b/cyber/base/atomic_rw_lock_test.cc @@ -14,13 +14,13 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/base/atomic_rw_lock.h" +#include "cyber/base/atomic_rw_lock.h" #include -#include "cybertron/base/reentrant_rw_lock.h" +#include "cyber/base/reentrant_rw_lock.h" #include "gtest/gtest.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace base { TEST(ReentrantRWLockTest, read_lock) { @@ -90,5 +90,5 @@ TEST(ReentrantRWLockTest, write_lock) { } } // namespace base -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/base/benchmark.md b/cyber/base/benchmark.md similarity index 88% rename from cybertron/base/benchmark.md rename to cyber/base/benchmark.md index e07b968b09b..1991e2e5eec 100644 --- a/cybertron/base/benchmark.md +++ b/cyber/base/benchmark.md @@ -1,5 +1,5 @@ ## Benchmarks -这里给出了cybertron中各无锁数据结构在经典场景下,与stl数据结构加锁在多线程并发场景下性能对比的数据,由于并发环境下有很大的随机性,以下数据选取的是大量实验得出的典型值。 +这里给出了cyber中各无锁数据结构在经典场景下,与stl数据结构加锁在多线程并发场景下性能对比的数据,由于并发环境下有很大的随机性,以下数据选取的是大量实验得出的典型值。 ### AtomicRWLock benchmark 写优先模式下,同时起一个线程加写锁,多个线程加读锁 diff --git a/cybertron/base/bounded_queue.h b/cyber/base/bounded_queue.h similarity index 96% rename from cybertron/base/bounded_queue.h rename to cyber/base/bounded_queue.h index 30bffe086ef..d9c23365e8d 100644 --- a/cybertron/base/bounded_queue.h +++ b/cyber/base/bounded_queue.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_BASE_BOUNDED_QUEUE_H_ -#define CYBERTRON_BASE_BOUNDED_QUEUE_H_ +#ifndef CYBER_BASE_BOUNDED_QUEUE_H_ +#define CYBER_BASE_BOUNDED_QUEUE_H_ #include #include @@ -24,11 +24,11 @@ #include #include -#include "cybertron/base/macros.h" -#include "cybertron/base/wait_strategy.h" +#include "cyber/base/macros.h" +#include "cyber/base/wait_strategy.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace base { template @@ -227,7 +227,7 @@ void BoundedQueue::BreakAllWait() { } } // namespace base -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_BASE_BOUNDED_QUEUE_H_ +#endif // CYBER_BASE_BOUNDED_QUEUE_H_ diff --git a/cybertron/base/bounded_queue_test.cc b/cyber/base/bounded_queue_test.cc similarity index 97% rename from cybertron/base/bounded_queue_test.cc rename to cyber/base/bounded_queue_test.cc index b07b531c182..88e1b3b3af6 100644 --- a/cybertron/base/bounded_queue_test.cc +++ b/cyber/base/bounded_queue_test.cc @@ -14,12 +14,12 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/base/bounded_queue.h" +#include "cyber/base/bounded_queue.h" #include #include "gtest/gtest.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace base { TEST(BoundedQueueTest, Enqueue) { @@ -141,5 +141,5 @@ TEST(BoundedQueueTest, busy_wait) { } } // namespace base -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/base/concurrent_object_pool.h b/cyber/base/concurrent_object_pool.h similarity index 94% rename from cybertron/base/concurrent_object_pool.h rename to cyber/base/concurrent_object_pool.h index 0db5d9b0498..ce7f5d50f97 100644 --- a/cybertron/base/concurrent_object_pool.h +++ b/cyber/base/concurrent_object_pool.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_BASE_CONCURRENT_OBJECT_POOL_H_ -#define CYBERTRON_BASE_CONCURRENT_OBJECT_POOL_H_ +#ifndef CYBER_BASE_CONCURRENT_OBJECT_POOL_H_ +#define CYBER_BASE_CONCURRENT_OBJECT_POOL_H_ #include #include @@ -25,10 +25,10 @@ #include #include -#include "cybertron/base/macros.h" +#include "cyber/base/macros.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace base { template @@ -160,7 +160,7 @@ void CCObjectPool::Dump() { } } // namespace base -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_BASE_CONCURRENT_OBJECT_POOL_H_ +#endif // CYBER_BASE_CONCURRENT_OBJECT_POOL_H_ diff --git a/cybertron/base/macros.h b/cyber/base/macros.h similarity index 91% rename from cybertron/base/macros.h rename to cyber/base/macros.h index 7e7479c3cf9..2ba41bb8cec 100644 --- a/cybertron/base/macros.h +++ b/cyber/base/macros.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_BASE_MACROS_H_ -#define CYBERTRON_BASE_MACROS_H_ +#ifndef CYBER_BASE_MACROS_H_ +#define CYBER_BASE_MACROS_H_ #if defined(__GNUC__) #define likely(x) (__builtin_expect((x), 1)) @@ -29,4 +29,4 @@ static inline void cpu_relax() { asm volatile("rep; nop" ::: "memory"); } -#endif // CYBERTRON_BASE_MACROS_H_ +#endif // CYBER_BASE_MACROS_H_ diff --git a/cybertron/base/object_pool.h b/cyber/base/object_pool.h similarity index 94% rename from cybertron/base/object_pool.h rename to cyber/base/object_pool.h index 45fec500c4b..04f58e07a95 100644 --- a/cybertron/base/object_pool.h +++ b/cyber/base/object_pool.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_BASE_OBJECT_POOL_H_ -#define CYBERTRON_BASE_OBJECT_POOL_H_ +#ifndef CYBER_BASE_OBJECT_POOL_H_ +#define CYBER_BASE_OBJECT_POOL_H_ #include #include @@ -25,10 +25,10 @@ #include #include -#include "cybertron/base/macros.h" +#include "cyber/base/macros.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace base { template @@ -141,7 +141,7 @@ void ObjectPool::Dump() { } } // namespace base -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_BASE_OBJECT_POOL_H_ +#endif // CYBER_BASE_OBJECT_POOL_H_ diff --git a/cybertron/base/object_pool_test.cc b/cyber/base/object_pool_test.cc similarity index 94% rename from cybertron/base/object_pool_test.cc rename to cyber/base/object_pool_test.cc index 8c56177baa4..727c16b3731 100644 --- a/cybertron/base/object_pool_test.cc +++ b/cyber/base/object_pool_test.cc @@ -14,12 +14,12 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/base/object_pool.h" +#include "cyber/base/object_pool.h" #include #include "gtest/gtest.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace base { class TestNode { @@ -46,5 +46,5 @@ TEST(ObjectPoolTest, get_object) { } } // namespace base -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/base/reentrant_rw_lock.h b/cyber/base/reentrant_rw_lock.h similarity index 94% rename from cybertron/base/reentrant_rw_lock.h rename to cyber/base/reentrant_rw_lock.h index 65a733cc5fe..41dfeaee29f 100644 --- a/cybertron/base/reentrant_rw_lock.h +++ b/cyber/base/reentrant_rw_lock.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_BASE_REENTRANT_RW_LOCK_H_ -#define CYBERTRON_BASE_REENTRANT_RW_LOCK_H_ +#ifndef CYBER_BASE_REENTRANT_RW_LOCK_H_ +#define CYBER_BASE_REENTRANT_RW_LOCK_H_ #include #include @@ -25,10 +25,10 @@ #include #include #include -#include "cybertron/base/rw_lock_guard.h" +#include "cyber/base/rw_lock_guard.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace base { static const std::thread::id NULL_THREAD_ID = std::thread::id(); @@ -134,7 +134,7 @@ inline void ReentrantRWLock::WriteUnlock() { } } // namespace base -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_BASE_REENTRANT_RW_LOCK_H_ +#endif // CYBER_BASE_REENTRANT_RW_LOCK_H_ diff --git a/cybertron/base/rw_lock_guard.h b/cyber/base/rw_lock_guard.h similarity index 90% rename from cybertron/base/rw_lock_guard.h rename to cyber/base/rw_lock_guard.h index d9e0bd7fd26..c99207fcbdb 100644 --- a/cybertron/base/rw_lock_guard.h +++ b/cyber/base/rw_lock_guard.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_BASE_RW_LOCK_GUARD_H_ -#define CYBERTRON_BASE_RW_LOCK_GUARD_H_ +#ifndef CYBER_BASE_RW_LOCK_GUARD_H_ +#define CYBER_BASE_RW_LOCK_GUARD_H_ #include #include @@ -27,7 +27,7 @@ #include namespace apollo { -namespace cybertron { +namespace cyber { namespace base { template @@ -59,7 +59,7 @@ class WriteLockGuard { }; } // namespace base -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_BASE_RW_LOCK_GUARD_H_ +#endif // CYBER_BASE_RW_LOCK_GUARD_H_ diff --git a/cybertron/base/signal.h b/cyber/base/signal.h similarity index 96% rename from cybertron/base/signal.h rename to cyber/base/signal.h index 969330468d3..ef0f8de5e27 100644 --- a/cybertron/base/signal.h +++ b/cyber/base/signal.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_BASE_SIGNAL_H_ -#define CYBERTRON_BASE_SIGNAL_H_ +#ifndef CYBER_BASE_SIGNAL_H_ +#define CYBER_BASE_SIGNAL_H_ #include #include @@ -24,7 +24,7 @@ #include namespace apollo { -namespace cybertron { +namespace cyber { namespace base { template @@ -187,7 +187,7 @@ class Slot { }; } // namespace base -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_BASE_SIGNAL_H_ +#endif // CYBER_BASE_SIGNAL_H_ diff --git a/cybertron/base/signal_test.cc b/cyber/base/signal_test.cc similarity index 97% rename from cybertron/base/signal_test.cc rename to cyber/base/signal_test.cc index cc1657a5f31..5f999cb74d6 100644 --- a/cybertron/base/signal_test.cc +++ b/cyber/base/signal_test.cc @@ -17,10 +17,10 @@ #include #include -#include "cybertron/base/signal.h" +#include "cyber/base/signal.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace base { TEST(SlotTest, zero_input_param) { @@ -135,5 +135,5 @@ TEST(SignalTest, module) { } } // namespace base -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/base/thread_pool.h b/cyber/base/thread_pool.h similarity index 92% rename from cybertron/base/thread_pool.h rename to cyber/base/thread_pool.h index da832ed8fb8..f105c002897 100644 --- a/cybertron/base/thread_pool.h +++ b/cyber/base/thread_pool.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_BASE_THREAD_POOL_H_ -#define CYBERTRON_BASE_THREAD_POOL_H_ +#ifndef CYBER_BASE_THREAD_POOL_H_ +#define CYBER_BASE_THREAD_POOL_H_ #include #include @@ -27,10 +27,10 @@ #include #include -#include "cybertron/base/bounded_queue.h" +#include "cyber/base/bounded_queue.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace base { class ThreadPool { @@ -97,7 +97,7 @@ inline ThreadPool::~ThreadPool() { } } // namespace base -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_BASE_THREAD_POOL_H_ +#endif // CYBER_BASE_THREAD_POOL_H_ diff --git a/cybertron/base/thread_safe_queue.h b/cyber/base/thread_safe_queue.h similarity index 92% rename from cybertron/base/thread_safe_queue.h rename to cyber/base/thread_safe_queue.h index fec8c88bb22..a17343feec7 100644 --- a/cybertron/base/thread_safe_queue.h +++ b/cyber/base/thread_safe_queue.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_BASE_THREAD_SAFE_QUEUE_H_ -#define CYBERTRON_BASE_THREAD_SAFE_QUEUE_H_ +#ifndef CYBER_BASE_THREAD_SAFE_QUEUE_H_ +#define CYBER_BASE_THREAD_SAFE_QUEUE_H_ #include #include @@ -24,7 +24,7 @@ #include namespace apollo { -namespace cybertron { +namespace cyber { namespace base { template @@ -86,7 +86,7 @@ class ThreadSafeQueue { }; } // namespace base -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_BASE_THREAD_SAFE_QUEUE_H_ +#endif // CYBER_BASE_THREAD_SAFE_QUEUE_H_ diff --git a/cybertron/base/unbounded_queue.h b/cyber/base/unbounded_queue.h similarity index 93% rename from cybertron/base/unbounded_queue.h rename to cyber/base/unbounded_queue.h index 6d71945ed52..afba5d257a3 100644 --- a/cybertron/base/unbounded_queue.h +++ b/cyber/base/unbounded_queue.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_BASE_UNBOUNDED_QUEUE_H_ -#define CYBERTRON_BASE_UNBOUNDED_QUEUE_H_ +#ifndef CYBER_BASE_UNBOUNDED_QUEUE_H_ +#define CYBER_BASE_UNBOUNDED_QUEUE_H_ #include #include @@ -23,7 +23,7 @@ #include namespace apollo { -namespace cybertron { +namespace cyber { namespace base { template @@ -105,7 +105,7 @@ class UnboundedQueue { }; } // namespace base -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_BASE_UNBOUNDED_QUEUE_H_ +#endif // CYBER_BASE_UNBOUNDED_QUEUE_H_ diff --git a/cybertron/base/wait_strategy.h b/cyber/base/wait_strategy.h similarity index 94% rename from cybertron/base/wait_strategy.h rename to cyber/base/wait_strategy.h index cd3139e511c..01388f6b5ee 100644 --- a/cybertron/base/wait_strategy.h +++ b/cyber/base/wait_strategy.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_BASE_WAIT_STRATEGY_H_ -#define CYBERTRON_BASE_WAIT_STRATEGY_H_ +#ifndef CYBER_BASE_WAIT_STRATEGY_H_ +#define CYBER_BASE_WAIT_STRATEGY_H_ #include #include @@ -24,7 +24,7 @@ #include namespace apollo { -namespace cybertron { +namespace cyber { namespace base { class WaitStrategy { @@ -116,7 +116,7 @@ class TimeoutBlockWaitStrategy : public WaitStrategy { }; } // namespace base -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_BASE_WAIT_STRATEGY_H_ +#endif // CYBER_BASE_WAIT_STRATEGY_H_ diff --git a/cybertron/binary.h b/cyber/binary.h similarity index 89% rename from cybertron/binary.h rename to cyber/binary.h index 787cd007103..090f4e0657a 100644 --- a/cybertron/binary.h +++ b/cyber/binary.h @@ -14,13 +14,13 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_BINARY_H_ -#define CYBERTRON_BINARY_H_ +#ifndef CYBER_BINARY_H_ +#define CYBER_BINARY_H_ #include namespace apollo { -namespace cybertron { +namespace cyber { class Binary { public: static std::string GetName() { return GetNameRef(); } @@ -30,7 +30,7 @@ class Binary { return binary_name; } }; -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_BINARY_H_ +#endif // CYBER_BINARY_H_ diff --git a/cybertron/blocker/BUILD b/cyber/blocker/BUILD similarity index 86% rename from cybertron/blocker/BUILD rename to cyber/blocker/BUILD index d5079a13ccb..3e30c4a6e5e 100644 --- a/cybertron/blocker/BUILD +++ b/cyber/blocker/BUILD @@ -22,8 +22,8 @@ cc_test( "blocker_manager_test.cc", ], deps = [ - "//cybertron", - "//cybertron/proto:unit_test_cc_proto", + "//cyber", + "//cyber/proto:unit_test_cc_proto", "@gtest//:main", ], ) @@ -42,8 +42,8 @@ cc_test( "blocker_test.cc", ], deps = [ - "//cybertron", - "//cybertron/proto:unit_test_cc_proto", + "//cyber", + "//cyber/proto:unit_test_cc_proto", "@gtest//:main", ], ) diff --git a/cybertron/blocker/blocker.h b/cyber/blocker/blocker.h similarity index 97% rename from cybertron/blocker/blocker.h rename to cyber/blocker/blocker.h index 86eacd85674..ddc3f14db31 100644 --- a/cybertron/blocker/blocker.h +++ b/cyber/blocker/blocker.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_BLOCKER_BLOCKER_H_ -#define CYBERTRON_BLOCKER_BLOCKER_H_ +#ifndef CYBER_BLOCKER_BLOCKER_H_ +#define CYBER_BLOCKER_BLOCKER_H_ #include #include @@ -27,7 +27,7 @@ #include namespace apollo { -namespace cybertron { +namespace cyber { namespace blocker { class BlockerBase { @@ -282,7 +282,7 @@ void Blocker::Notify(const MessagePtr& msg) { } } // namespace blocker -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_BLOCKER_BLOCKER_H_ +#endif // CYBER_BLOCKER_BLOCKER_H_ diff --git a/cybertron/blocker/blocker_manager.cc b/cyber/blocker/blocker_manager.cc similarity index 93% rename from cybertron/blocker/blocker_manager.cc rename to cyber/blocker/blocker_manager.cc index 8269cc5a832..bb1017fdf06 100644 --- a/cybertron/blocker/blocker_manager.cc +++ b/cyber/blocker/blocker_manager.cc @@ -14,10 +14,10 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/blocker/blocker_manager.h" +#include "cyber/blocker/blocker_manager.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace blocker { BlockerManager::BlockerManager() {} @@ -40,5 +40,5 @@ void BlockerManager::Reset() { } } // namespace blocker -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/blocker/blocker_manager.h b/cyber/blocker/blocker_manager.h similarity index 95% rename from cybertron/blocker/blocker_manager.h rename to cyber/blocker/blocker_manager.h index bf3958508de..7d5e9c78ff6 100644 --- a/cybertron/blocker/blocker_manager.h +++ b/cyber/blocker/blocker_manager.h @@ -14,18 +14,18 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_BLOCKER_BLOCKER_MANAGER_H_ -#define CYBERTRON_BLOCKER_BLOCKER_MANAGER_H_ +#ifndef CYBER_BLOCKER_BLOCKER_MANAGER_H_ +#define CYBER_BLOCKER_BLOCKER_MANAGER_H_ #include #include #include #include -#include "cybertron/blocker/blocker.h" +#include "cyber/blocker/blocker.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace blocker { class BlockerManager { @@ -151,7 +151,7 @@ std::shared_ptr> BlockerManager::GetOrCreateBlocker( } } // namespace blocker -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_BLOCKER_BLOCKER_MANAGER_H_ +#endif // CYBER_BLOCKER_BLOCKER_MANAGER_H_ diff --git a/cybertron/blocker/blocker_manager_test.cc b/cyber/blocker/blocker_manager_test.cc similarity index 83% rename from cybertron/blocker/blocker_manager_test.cc rename to cyber/blocker/blocker_manager_test.cc index be6b897cfd9..ca04d42cdb5 100644 --- a/cybertron/blocker/blocker_manager_test.cc +++ b/cyber/blocker/blocker_manager_test.cc @@ -16,15 +16,15 @@ #include "gtest/gtest.h" -#include "cybertron/blocker/blocker_manager.h" -#include "cybertron/proto/unit_test.pb.h" +#include "cyber/blocker/blocker_manager.h" +#include "cyber/proto/unit_test.pb.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace blocker { -using apollo::cybertron::proto::UnitTest; +using apollo::cyber::proto::UnitTest; } // namespace blocker -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/blocker/blocker_test.cc b/cyber/blocker/blocker_test.cc similarity index 94% rename from cybertron/blocker/blocker_test.cc rename to cyber/blocker/blocker_test.cc index 5157dbeddc9..8b36e01acd6 100644 --- a/cybertron/blocker/blocker_test.cc +++ b/cyber/blocker/blocker_test.cc @@ -17,14 +17,14 @@ #include #include -#include "cybertron/blocker/blocker.h" -#include "cybertron/proto/unit_test.pb.h" +#include "cyber/blocker/blocker.h" +#include "cyber/proto/unit_test.pb.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace blocker { -using apollo::cybertron::proto::UnitTest; +using apollo::cyber::proto::UnitTest; TEST(BlockerTest, constructor) { BlockerAttr attr(10, "channel"); @@ -105,5 +105,5 @@ TEST(BlockerTest, subscribe) { } } // namespace blocker -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/blocker/intra_reader.h b/cyber/blocker/intra_reader.h similarity index 92% rename from cybertron/blocker/intra_reader.h rename to cyber/blocker/intra_reader.h index f2bc00927b1..82e38de2adc 100644 --- a/cybertron/blocker/intra_reader.h +++ b/cyber/blocker/intra_reader.h @@ -14,24 +14,24 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_BLOCKER_INTRA_READER_H_ -#define CYBERTRON_BLOCKER_INTRA_READER_H_ +#ifndef CYBER_BLOCKER_INTRA_READER_H_ +#define CYBER_BLOCKER_INTRA_READER_H_ #include #include #include -#include "cybertron/blocker/blocker_manager.h" -#include "cybertron/common/log.h" -#include "cybertron/node/reader.h" -#include "cybertron/time/time.h" +#include "cyber/blocker/blocker_manager.h" +#include "cyber/common/log.h" +#include "cyber/node/reader.h" +#include "cyber/time/time.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace blocker { template -class IntraReader : public apollo::cybertron::Reader { +class IntraReader : public apollo::cyber::Reader { public: using MessagePtr = std::shared_ptr; using Callback = std::function&)>; @@ -196,14 +196,14 @@ auto IntraReader::End() const -> Iterator { template void IntraReader::OnMessage(const MessagePtr& msg_ptr) { this->second_to_lastest_recv_time_sec_ = this->latest_recv_time_sec_; - this->latest_recv_time_sec_ = apollo::cybertron::Time::Now().ToSecond(); + this->latest_recv_time_sec_ = apollo::cyber::Time::Now().ToSecond(); if (msg_callback_ != nullptr) { msg_callback_(msg_ptr); } } } // namespace blocker -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_BLOCKER_INTRA_READER_H_ +#endif // CYBER_BLOCKER_INTRA_READER_H_ diff --git a/cybertron/blocker/intra_writer.h b/cyber/blocker/intra_writer.h similarity index 88% rename from cybertron/blocker/intra_writer.h rename to cyber/blocker/intra_writer.h index 99c9af1a633..98261469245 100644 --- a/cybertron/blocker/intra_writer.h +++ b/cyber/blocker/intra_writer.h @@ -14,20 +14,20 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_BLOCKER_INTRA_WRITER_H_ -#define CYBERTRON_BLOCKER_INTRA_WRITER_H_ +#ifndef CYBER_BLOCKER_INTRA_WRITER_H_ +#define CYBER_BLOCKER_INTRA_WRITER_H_ #include -#include "cybertron/blocker/blocker_manager.h" -#include "cybertron/node/writer.h" +#include "cyber/blocker/blocker_manager.h" +#include "cyber/node/writer.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace blocker { template -class IntraWriter : public apollo::cybertron::Writer { +class IntraWriter : public apollo::cyber::Writer { public: using MessagePtr = std::shared_ptr; using BlockerManagerPtr = std::shared_ptr; @@ -93,7 +93,7 @@ bool IntraWriter::Write(const MessagePtr& msg_ptr) { } } // namespace blocker -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_BLOCKER_INTRA_WRITER_H_ +#endif // CYBER_BLOCKER_INTRA_WRITER_H_ diff --git a/cybertron/class_loader/BUILD b/cyber/class_loader/BUILD similarity index 92% rename from cybertron/class_loader/BUILD rename to cyber/class_loader/BUILD index 007cd854af0..f681e488303 100644 --- a/cybertron/class_loader/BUILD +++ b/cyber/class_loader/BUILD @@ -16,8 +16,8 @@ cc_library( "utility/class_loader_utility.h", ], deps = [ - "//cybertron/common:log", - "//cybertron:init", + "//cyber/common:log", + "//cyber:init", ], linkopts = [ "-lPocoFoundation", diff --git a/cybertron/class_loader/class_loader.cc b/cyber/class_loader/class_loader.cc similarity index 95% rename from cybertron/class_loader/class_loader.cc rename to cyber/class_loader/class_loader.cc index cdb4c070075..3c85e94b1b4 100644 --- a/cybertron/class_loader/class_loader.cc +++ b/cyber/class_loader/class_loader.cc @@ -13,10 +13,10 @@ * See the License for the specific language governing permissions and * limitations under the License. *****************************************************************************/ -#include "cybertron/class_loader/class_loader.h" +#include "cyber/class_loader/class_loader.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace class_loader { ClassLoader::ClassLoader(const std::string& library_path) : library_path_(library_path), @@ -62,5 +62,5 @@ int ClassLoader::UnloadLibrary() { const std::string ClassLoader::GetLibraryPath() const { return library_path_; } } // namespace class_loader -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/class_loader/class_loader.h b/cyber/class_loader/class_loader.h similarity index 92% rename from cybertron/class_loader/class_loader.h rename to cyber/class_loader/class_loader.h index ea0440c9338..30435233256 100644 --- a/cybertron/class_loader/class_loader.h +++ b/cyber/class_loader/class_loader.h @@ -13,8 +13,8 @@ * See the License for the specific language governing permissions and * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_CLASS_LOADER_CLASS_LOADER_H_ -#define CYBERTRON_CLASS_LOADER_CLASS_LOADER_H_ +#ifndef CYBER_CLASS_LOADER_CLASS_LOADER_H_ +#define CYBER_CLASS_LOADER_CLASS_LOADER_H_ #include #include @@ -22,10 +22,10 @@ #include #include -#include "cybertron/class_loader/class_loader_register_macro.h" +#include "cyber/class_loader/class_loader_register_macro.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace class_loader { /** @@ -105,6 +105,6 @@ void ClassLoader::OnClassObjDeleter(Base* obj) { } } // namespace class_loader -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_CLASS_LOADER_CLASS_LOADER_H_ +#endif // CYBER_CLASS_LOADER_CLASS_LOADER_H_ diff --git a/cybertron/class_loader/class_loader_manager.cc b/cyber/class_loader/class_loader_manager.cc similarity index 96% rename from cybertron/class_loader/class_loader_manager.cc rename to cyber/class_loader/class_loader_manager.cc index 520c874030c..1ac95d6a704 100644 --- a/cybertron/class_loader/class_loader_manager.cc +++ b/cyber/class_loader/class_loader_manager.cc @@ -13,10 +13,10 @@ * See the License for the specific language governing permissions and * limitations under the License. *****************************************************************************/ -#include "cybertron/class_loader/class_loader_manager.h" +#include "cyber/class_loader/class_loader_manager.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace class_loader { ClassLoaderManager::ClassLoaderManager() {} @@ -81,5 +81,5 @@ void ClassLoaderManager::UnloadAllLibrary() { } } } // namespace class_loader -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/class_loader/class_loader_manager.h b/cyber/class_loader/class_loader_manager.h similarity index 93% rename from cybertron/class_loader/class_loader_manager.h rename to cyber/class_loader/class_loader_manager.h index 32218f90231..c67ec1d13b1 100644 --- a/cybertron/class_loader/class_loader_manager.h +++ b/cyber/class_loader/class_loader_manager.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_CLASS_LOADER_CLASS_LOADER_MANAGER_H_ -#define CYBERTRON_CLASS_LOADER_CLASS_LOADER_MANAGER_H_ +#ifndef CYBER_CLASS_LOADER_CLASS_LOADER_MANAGER_H_ +#define CYBER_CLASS_LOADER_CLASS_LOADER_MANAGER_H_ #include #include @@ -23,10 +23,10 @@ #include #include -#include "cybertron/class_loader/class_loader.h" +#include "cyber/class_loader/class_loader.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace class_loader { class ClassLoaderManager { @@ -105,7 +105,7 @@ std::vector ClassLoaderManager::GetValidClassNames() { } } // namespace class_loader -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_CLASS_LOADER_CLASS_LOADER_MANAGER_H_ +#endif // CYBER_CLASS_LOADER_CLASS_LOADER_MANAGER_H_ diff --git a/cybertron/class_loader/class_loader_register_macro.h b/cyber/class_loader/class_loader_register_macro.h similarity index 83% rename from cybertron/class_loader/class_loader_register_macro.h rename to cyber/class_loader/class_loader_register_macro.h index 3b1415cd887..c0fc48ebbf6 100644 --- a/cybertron/class_loader/class_loader_register_macro.h +++ b/cyber/class_loader/class_loader_register_macro.h @@ -14,16 +14,16 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_CLASS_LOADER_CLASS_LOADER_REGISTER_MACRO_H_ -#define CYBERTRON_CLASS_LOADER_CLASS_LOADER_REGISTER_MACRO_H_ +#ifndef CYBER_CLASS_LOADER_CLASS_LOADER_REGISTER_MACRO_H_ +#define CYBER_CLASS_LOADER_CLASS_LOADER_REGISTER_MACRO_H_ -#include "cybertron/class_loader/utility/class_loader_utility.h" +#include "cyber/class_loader/utility/class_loader_utility.h" #define CLASS_LOADER_REGISTER_CLASS_INTERNAL(Derived, Base, UniqueID) \ namespace { \ struct ProxyType##UniqueID { \ ProxyType##UniqueID() { \ - apollo::cybertron::class_loader::utility::RegisterClass( \ + apollo::cyber::class_loader::utility::RegisterClass( \ #Derived, #Base); \ } \ }; \ @@ -37,4 +37,4 @@ #define CLASS_LOADER_REGISTER_CLASS(Derived, Base) \ CLASS_LOADER_REGISTER_CLASS_INTERNAL_1(Derived, Base, __COUNTER__) -#endif // CYBERTRON_CLASS_LOADER_CLASS_LOADER_REGISTER_MACRO_H_ +#endif // CYBER_CLASS_LOADER_CLASS_LOADER_REGISTER_MACRO_H_ diff --git a/cybertron/class_loader/utility/class_factory.cc b/cyber/class_loader/utility/class_factory.cc similarity index 94% rename from cybertron/class_loader/utility/class_factory.cc rename to cyber/class_loader/utility/class_factory.cc index 0d1b2f9f673..96da23bcd0c 100644 --- a/cybertron/class_loader/utility/class_factory.cc +++ b/cyber/class_loader/utility/class_factory.cc @@ -13,11 +13,11 @@ * See the License for the specific language governing permissions and * limitations under the License. *****************************************************************************/ -#include "cybertron/class_loader/utility/class_factory.h" -#include "cybertron/class_loader/class_loader.h" +#include "cyber/class_loader/utility/class_factory.h" +#include "cyber/class_loader/class_loader.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace class_loader { namespace utility { @@ -78,5 +78,5 @@ const std::string AbstractClassFactoryBase::GetClassName() const { } // namespace utility } // namespace class_loader -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/class_loader/utility/class_factory.h b/cyber/class_loader/utility/class_factory.h similarity index 92% rename from cybertron/class_loader/utility/class_factory.h rename to cyber/class_loader/utility/class_factory.h index 0ea8d536a2c..aaf8991ce9c 100644 --- a/cybertron/class_loader/utility/class_factory.h +++ b/cyber/class_loader/utility/class_factory.h @@ -13,15 +13,15 @@ * See the License for the specific language governing permissions and * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_CLASS_LOADER_UTILITY_CLASS_FACTORY_H_ -#define CYBERTRON_CLASS_LOADER_UTILITY_CLASS_FACTORY_H_ +#ifndef CYBER_CLASS_LOADER_UTILITY_CLASS_FACTORY_H_ +#define CYBER_CLASS_LOADER_UTILITY_CLASS_FACTORY_H_ #include #include #include namespace apollo { -namespace cybertron { +namespace cyber { namespace class_loader { class ClassLoader; @@ -78,7 +78,7 @@ class ClassFactory : public AbstractClassFactory { } // namespace utility } // namespace class_loader -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_CLASS_LOADER_UTILITY_CLASS_FACTORY_H_ +#endif // CYBER_CLASS_LOADER_UTILITY_CLASS_FACTORY_H_ diff --git a/cybertron/class_loader/utility/class_loader_utility.cc b/cyber/class_loader/utility/class_loader_utility.cc similarity index 98% rename from cybertron/class_loader/utility/class_loader_utility.cc rename to cyber/class_loader/utility/class_loader_utility.cc index 2e3e8d49f17..8d5d4abf2bd 100644 --- a/cybertron/class_loader/utility/class_loader_utility.cc +++ b/cyber/class_loader/utility/class_loader_utility.cc @@ -14,12 +14,12 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/class_loader/utility/class_loader_utility.h" +#include "cyber/class_loader/utility/class_loader_utility.h" -#include "cybertron/class_loader/class_loader.h" +#include "cyber/class_loader/class_loader.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace class_loader { namespace utility { @@ -285,5 +285,5 @@ void UnloadLibrary(const std::string& library_path, ClassLoader* loader) { } // End namespace utility } // End namespace class_loader -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/class_loader/utility/class_loader_utility.h b/cyber/class_loader/utility/class_loader_utility.h similarity index 93% rename from cybertron/class_loader/utility/class_loader_utility.h rename to cyber/class_loader/utility/class_loader_utility.h index c3ba83ce66e..67b046c6cfa 100644 --- a/cybertron/class_loader/utility/class_loader_utility.h +++ b/cyber/class_loader/utility/class_loader_utility.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_CLASS_LOADER_CLASS_LOADER_UTILITY_H_ -#define CYBERTRON_CLASS_LOADER_CLASS_LOADER_UTILITY_H_ +#ifndef CYBER_CLASS_LOADER_CLASS_LOADER_UTILITY_H_ +#define CYBER_CLASS_LOADER_CLASS_LOADER_UTILITY_H_ #include #include @@ -28,14 +28,14 @@ #include #include -#include "cybertron/class_loader/utility/class_factory.h" -#include "cybertron/common/log.h" +#include "cyber/class_loader/utility/class_factory.h" +#include "cyber/common/log.h" /** * class register implement */ namespace apollo { -namespace cybertron { +namespace cyber { namespace class_loader { class ClassLoader; @@ -129,6 +129,6 @@ std::vector GetValidClassNames(ClassLoader* loader) { } // End namespace utility } // End namespace class_loader -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_CLASS_LOADER_CLASS_LOADER_UTILITY_H_ +#endif // CYBER_CLASS_LOADER_CLASS_LOADER_UTILITY_H_ diff --git a/cybertron/common/BUILD b/cyber/common/BUILD similarity index 64% rename from cybertron/common/BUILD rename to cyber/common/BUILD index 1b4a6995494..17b781aa152 100644 --- a/cybertron/common/BUILD +++ b/cyber/common/BUILD @@ -5,14 +5,14 @@ package(default_visibility = ["//visibility:public"]) cc_library( name = "common", deps = [ - "//cybertron/common:environment", - "//cybertron/common:file", - "//cybertron/common:global_data", - "//cybertron/common:log", - "//cybertron/common:macros", - "//cybertron/common:time_conversion", - "//cybertron/common:types", - "//cybertron/common:util", + "//cyber/common:environment", + "//cyber/common:file", + "//cyber/common:global_data", + "//cyber/common:log", + "//cyber/common:macros", + "//cyber/common:time_conversion", + "//cyber/common:types", + "//cyber/common:util", ], ) @@ -25,7 +25,7 @@ cc_library( "file.h", ], deps = [ - "//cybertron/common:log", + "//cyber/common:log", ], ) @@ -37,8 +37,8 @@ cc_test( "file_test.cc", ], deps = [ - "//cybertron", - "//cybertron/proto:unit_test_cc_proto", + "//cyber", + "//cyber/proto:unit_test_cc_proto", "@gtest//:main", ], ) @@ -49,7 +49,7 @@ cc_library( "log.h", ], deps = [ - "//cybertron:binary", + "//cyber:binary", ], ) @@ -60,7 +60,7 @@ cc_test( "logfileobject_test.cc", ], deps = [ - "//cybertron", + "//cyber", "@gtest//:main", ], ) @@ -72,7 +72,7 @@ cc_test( "log_test.cc", ], deps = [ - "//cybertron", + "//cyber", "@gtest//:main", ], ) @@ -83,7 +83,7 @@ cc_library( "environment.h", ], deps = [ -#"//cybertron/common:log", +#"//cyber/common:log", ], ) @@ -96,13 +96,13 @@ cc_library( "global_data.h", ], deps = [ - "//cybertron/base:atomic_hash_map", - "//cybertron/base:atomic_rw_lock", - "//cybertron/common:environment", - "//cybertron/common:file", - "//cybertron/common:macros", - "//cybertron/common:util", - "//cybertron/proto:cyber_config_cc_proto", + "//cyber/base:atomic_hash_map", + "//cyber/base:atomic_rw_lock", + "//cyber/common:environment", + "//cyber/common:file", + "//cyber/common:macros", + "//cyber/common:util", + "//cyber/proto:cyber_config_cc_proto", ], ) diff --git a/cybertron/common/environment.h b/cyber/common/environment.h similarity index 82% rename from cybertron/common/environment.h rename to cyber/common/environment.h index 045ae6cd9ee..1df45c132ab 100644 --- a/cybertron/common/environment.h +++ b/cyber/common/environment.h @@ -14,15 +14,15 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_COMMON_ENVIRONMENT_H_ -#define CYBERTRON_COMMON_ENVIRONMENT_H_ +#ifndef CYBER_COMMON_ENVIRONMENT_H_ +#define CYBER_COMMON_ENVIRONMENT_H_ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace common { inline const std::string GetEnv(const std::string& var_name) { @@ -36,12 +36,12 @@ inline const std::string GetEnv(const std::string& var_name) { } inline const std::string WorkRoot() { - std::string work_root = GetEnv("CYBERTRON_PATH"); - // ensure variable CYBERTRON_PATH has been set. + std::string work_root = GetEnv("CYBER_PATH"); + // ensure variable CYBER_PATH has been set. // TODO(fengkaiwen01) need a better error handling mechanism // assert(!work_root.empty()); if (work_root.empty()) { - work_root = "/apollo/cybertron"; + work_root = "/apollo/cyber"; } return work_root; } @@ -59,7 +59,7 @@ inline const std::string ModuleRoot() { } } // namespace common -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_COMMON_ENVIRONMENT_H_ +#endif // CYBER_COMMON_ENVIRONMENT_H_ diff --git a/cybertron/common/environment_test.cc b/cyber/common/environment_test.cc similarity index 89% rename from cybertron/common/environment_test.cc rename to cyber/common/environment_test.cc index ff013b3b40d..e065725c529 100644 --- a/cybertron/common/environment_test.cc +++ b/cyber/common/environment_test.cc @@ -18,10 +18,10 @@ #include -#include "cybertron/common/environment.h" +#include "cyber/common/environment.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace common { TEST(EnvironmentTest, get_env) { @@ -36,10 +36,10 @@ TEST(EnvironmentTest, get_env) { TEST(EnvironmentTest, work_root) { std::string before = WorkRoot(); - unsetenv("CYBERTRON_PATH"); - std::string after = GetEnv("CYBERTRON_PATH"); + unsetenv("CYBER_PATH"); + std::string after = GetEnv("CYBER_PATH"); EXPECT_EQ(after, ""); - setenv("CYBERTRON_PATH", before.c_str(), 1); + setenv("CYBER_PATH", before.c_str(), 1); after = WorkRoot(); EXPECT_EQ(after, before); } @@ -58,5 +58,5 @@ TEST(EnvironmentTest, module_root) { } } // namespace common -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/common/file.cc b/cyber/common/file.cc similarity index 98% rename from cybertron/common/file.cc rename to cyber/common/file.cc index 6a3a9c3cc2d..9daeaf1c966 100644 --- a/cybertron/common/file.cc +++ b/cyber/common/file.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/common/file.h" +#include "cyber/common/file.h" #include #include @@ -24,7 +24,7 @@ #include namespace apollo { -namespace cybertron { +namespace cyber { namespace common { bool GetContent(const std::string &file_name, std::string *content) { @@ -181,5 +181,5 @@ std::string GetFileName(const std::string &path) { std::string GetCurrentPath() { return std::string(get_current_dir_name()); } } // namespace common -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/common/file.h b/cyber/common/file.h similarity index 97% rename from cybertron/common/file.h rename to cyber/common/file.h index 1ac6677f16f..2b687fa141e 100644 --- a/cybertron/common/file.h +++ b/cyber/common/file.h @@ -18,8 +18,8 @@ * @file */ -#ifndef CYBERTRON_COMMON_FILE_H_ -#define CYBERTRON_COMMON_FILE_H_ +#ifndef CYBER_COMMON_FILE_H_ +#define CYBER_COMMON_FILE_H_ #include #include @@ -31,7 +31,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "google/protobuf/io/zero_copy_stream_impl.h" #include "google/protobuf/text_format.h" @@ -40,7 +40,7 @@ * @brief apollo::common::util */ namespace apollo { -namespace cybertron { +namespace cyber { namespace common { template @@ -232,7 +232,7 @@ std::string GetFileName(const std::string &path); std::string GetCurrentPath(); } // namespace common -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_COMMON_FILE_H_ +#endif // CYBER_COMMON_FILE_H_ diff --git a/cybertron/common/file_test.cc b/cyber/common/file_test.cc similarity index 92% rename from cybertron/common/file_test.cc rename to cyber/common/file_test.cc index 2ed493b372e..9f4b102dddc 100644 --- a/cybertron/common/file_test.cc +++ b/cyber/common/file_test.cc @@ -19,17 +19,17 @@ #include #include -#include "cybertron/common/file.h" -#include "cybertron/proto/unit_test.pb.h" +#include "cyber/common/file.h" +#include "cyber/proto/unit_test.pb.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace common { TEST(FileTest, proto_set_get_test) { - apollo::cybertron::proto::UnitTest message; + apollo::cyber::proto::UnitTest message; message.set_class_name("FileTest"); - apollo::cybertron::proto::UnitTest read_message; + apollo::cyber::proto::UnitTest read_message; EXPECT_FALSE(SetProtoToASCIIFile(message, -1)); EXPECT_FALSE(SetProtoToASCIIFile(message, "not_exists_dir/message.proto")); EXPECT_TRUE(SetProtoToASCIIFile(message, "message.ascii")); @@ -50,9 +50,9 @@ TEST(FileTest, proto_set_get_test) { } TEST(FileTest, file_utils_test) { - apollo::cybertron::proto::UnitTest message; + apollo::cyber::proto::UnitTest message; message.set_class_name("FileTest"); - apollo::cybertron::proto::UnitTest read_message; + apollo::cyber::proto::UnitTest read_message; EXPECT_TRUE(SetProtoToBinaryFile(message, "message.binary")); std::string content; @@ -113,5 +113,5 @@ TEST(FileTest, file_utils_test) { } } // namespace common -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/common/global_data.cc b/cyber/common/global_data.cc similarity index 92% rename from cybertron/common/global_data.cc rename to cyber/common/global_data.cc index b2cdb09357c..3588d5c5c77 100644 --- a/cybertron/common/global_data.cc +++ b/cyber/common/global_data.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/common/global_data.h" +#include "cyber/common/global_data.h" #include #include @@ -22,12 +22,12 @@ #include #include -#include "cybertron/common/environment.h" -#include "cybertron/common/file.h" -#include "cybertron/common/util.h" +#include "cyber/common/environment.h" +#include "cyber/common/file.h" +#include "cyber/common/util.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace common { AtomicHashMap GlobalData::node_id_map_; @@ -46,7 +46,7 @@ GlobalData::GlobalData() { process_name_ = "default_" + std::to_string(process_id_); is_reality_mode_ = (config_.has_run_mode_conf() && config_.run_mode_conf().run_mode() == - apollo::cybertron::proto::RunMode::MODE_SIMULATION) + apollo::cyber::proto::RunMode::MODE_SIMULATION) ? false : true; @@ -88,9 +88,9 @@ void GlobalData::InitHostInfo() { } void GlobalData::InitConfig() { - auto config_path = GetAbsolutePath(WorkRoot(), "conf/cybertron.pb.conf"); + auto config_path = GetAbsolutePath(WorkRoot(), "conf/cyber.pb.conf"); if (!GetProtoFromFile(config_path, &config_)) { - AERROR << "read cybertron global conf failed!"; + AERROR << "read cyber global conf failed!"; } } @@ -189,5 +189,5 @@ std::string GlobalData::GetTaskNameById(uint64_t id) { } } // namespace common -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/common/global_data.h b/cyber/common/global_data.h similarity index 83% rename from cybertron/common/global_data.h rename to cyber/common/global_data.h index 762e87acce1..6f2c032cdff 100644 --- a/cybertron/common/global_data.h +++ b/cyber/common/global_data.h @@ -14,24 +14,24 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_COMMON_GLOBAL_DATA_H_ -#define CYBERTRON_COMMON_GLOBAL_DATA_H_ +#ifndef CYBER_COMMON_GLOBAL_DATA_H_ +#define CYBER_COMMON_GLOBAL_DATA_H_ #include #include -#include "cybertron/base/atomic_hash_map.h" -#include "cybertron/base/atomic_rw_lock.h" -#include "cybertron/common/log.h" -#include "cybertron/common/macros.h" -#include "cybertron/proto/cyber_config.pb.h" +#include "cyber/base/atomic_hash_map.h" +#include "cyber/base/atomic_rw_lock.h" +#include "cyber/common/log.h" +#include "cyber/common/macros.h" +#include "cyber/proto/cyber_config.pb.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace common { -using ::apollo::cybertron::base::AtomicHashMap; -using ::apollo::cybertron::proto::CyberConfig; +using ::apollo::cyber::base::AtomicHashMap; +using ::apollo::cyber::proto::CyberConfig; class GlobalData { public: @@ -92,7 +92,7 @@ class GlobalData { }; } // namespace common -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_COMMON_GLOBAL_DATA_H_ +#endif // CYBER_COMMON_GLOBAL_DATA_H_ diff --git a/cybertron/common/log.h b/cyber/common/log.h similarity index 90% rename from cybertron/common/log.h rename to cyber/common/log.h index bbfcd7998ce..c10b9e35f7e 100644 --- a/cybertron/common/log.h +++ b/cyber/common/log.h @@ -18,11 +18,11 @@ * @log */ -#ifndef CYBERTRON_COMMON_LOG_H_ -#define CYBERTRON_COMMON_LOG_H_ +#ifndef CYBER_COMMON_LOG_H_ +#define CYBER_COMMON_LOG_H_ #include -#include "cybertron/binary.h" +#include "cyber/binary.h" #include "glog/logging.h" #include "glog/raw_logging.h" @@ -37,7 +37,7 @@ #define ADEBUG_MODULE(module) \ VLOG(4) << LEFT_BRACKET << (strcmp(module, DEFAULT_NAME) != 0 \ ? module \ - : apollo::cybertron::Binary::GetName()) \ + : apollo::cyber::Binary::GetName()) \ << RIGHT_BRACKET << "[DEBUG] " #define ADEBUG ADEBUG_MODULE(MODULE_NAME) #define AINFO ALOG_MODULE(MODULE_NAME, INFO) @@ -59,7 +59,7 @@ ? google::LogMessage(__FILE__, __LINE__, google::INFO).stream() \ << LEFT_BRACKET << module << RIGHT_BRACKET \ : google::LogMessage(__FILE__, __LINE__, google::INFO).stream() \ - << LEFT_BRACKET << apollo::cybertron::Binary::GetName() \ + << LEFT_BRACKET << apollo::cyber::Binary::GetName() \ << RIGHT_BRACKET) #define ALOG_MODULE_STREAM_WARN(module) \ @@ -67,7 +67,7 @@ ? google::LogMessage(__FILE__, __LINE__, google::WARNING).stream() \ << LEFT_BRACKET << module << RIGHT_BRACKET \ : google::LogMessage(__FILE__, __LINE__, google::WARNING).stream() \ - << LEFT_BRACKET << apollo::cybertron::Binary::GetName() \ + << LEFT_BRACKET << apollo::cyber::Binary::GetName() \ << RIGHT_BRACKET) #define ALOG_MODULE_STREAM_ERROR(module) \ @@ -75,7 +75,7 @@ ? google::LogMessage(__FILE__, __LINE__, google::ERROR).stream() \ << LEFT_BRACKET << module << RIGHT_BRACKET \ : google::LogMessage(__FILE__, __LINE__, google::ERROR).stream() \ - << LEFT_BRACKET << apollo::cybertron::Binary::GetName() \ + << LEFT_BRACKET << apollo::cyber::Binary::GetName() \ << RIGHT_BRACKET) #define ALOG_MODULE_STREAM_FATAL(module) \ @@ -83,7 +83,7 @@ ? google::LogMessage(__FILE__, __LINE__, google::FATAL).stream() \ << LEFT_BRACKET << module << RIGHT_BRACKET \ : google::LogMessage(__FILE__, __LINE__, google::FATAL).stream() \ - << LEFT_BRACKET << apollo::cybertron::Binary::GetName() \ + << LEFT_BRACKET << apollo::cyber::Binary::GetName() \ << RIGHT_BRACKET) #define AINFO_IF(cond) ALOG_IF(INFO, cond, MODULE_NAME) @@ -126,4 +126,4 @@ return val; \ } -#endif // CYBERTRON_COMMON_LOG_H_ +#endif // CYBER_COMMON_LOG_H_ diff --git a/cybertron/common/log_test.cc b/cyber/common/log_test.cc similarity index 92% rename from cybertron/common/log_test.cc rename to cyber/common/log_test.cc index 95552c4ea30..6bab3ea1801 100644 --- a/cybertron/common/log_test.cc +++ b/cyber/common/log_test.cc @@ -14,16 +14,16 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "glog/logging.h" #include "gtest/gtest.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace common { TEST(LogTest, TestAll) { AINFO << "11111"; } } // namespace common -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/common/logfileobject_test.cc b/cyber/common/logfileobject_test.cc similarity index 85% rename from cybertron/common/logfileobject_test.cc rename to cyber/common/logfileobject_test.cc index 8a5e691578f..7c312e1927c 100644 --- a/cybertron/common/logfileobject_test.cc +++ b/cyber/common/logfileobject_test.cc @@ -18,12 +18,12 @@ #include #include -#include "cybertron/cybertron.h" -#include "cybertron/logger/log_file_object.h" -#include "cybertron/time/time.h" +#include "cyber/cyber.h" +#include "cyber/logger/log_file_object.h" +#include "cyber/time/time.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace logger { TEST(LogFileObjectTest, init_and_write) { @@ -32,12 +32,12 @@ TEST(LogFileObjectTest, init_and_write) { logfileobject.SetBasename("base"); time_t timep; time(&timep); - std::string message = "cybertron logger test"; + std::string message = "cyber logger test"; logfileobject.Write(false, timep, message.c_str(), 20); logfileobject.SetExtension("unittest"); logfileobject.Flush(); } } // namespace logger -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/common/macros.h b/cyber/common/macros.h similarity index 94% rename from cybertron/common/macros.h rename to cyber/common/macros.h index e7c6feff285..827160a7a09 100644 --- a/cybertron/common/macros.h +++ b/cyber/common/macros.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_COMMON_MACROS_H_ -#define CYBERTRON_COMMON_MACROS_H_ +#ifndef CYBER_COMMON_MACROS_H_ +#define CYBER_COMMON_MACROS_H_ #include @@ -41,4 +41,4 @@ classname(); \ DISALLOW_COPY_AND_ASSIGN(classname) -#endif // CYBERTRON_COMMON_MACROS_H_ +#endif // CYBER_COMMON_MACROS_H_ diff --git a/cybertron/common/time_conversion.h b/cyber/common/time_conversion.h similarity index 96% rename from cybertron/common/time_conversion.h rename to cyber/common/time_conversion.h index aaf9b4a8ce8..64f563eec52 100644 --- a/cybertron/common/time_conversion.h +++ b/cyber/common/time_conversion.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_COMMON_TIME_CONVERSION_H_ -#define CYBERTRON_COMMON_TIME_CONVERSION_H_ +#ifndef CYBER_COMMON_TIME_CONVERSION_H_ +#define CYBER_COMMON_TIME_CONVERSION_H_ #include #include @@ -25,7 +25,7 @@ #include namespace apollo { -namespace cybertron { +namespace cyber { namespace common { // Leap seconds change every a few years. See below for details. @@ -137,7 +137,7 @@ inline std::string UnixSecondsToString( } } // namespace common -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_COMMON_TIME_CONVERSION_H_ +#endif // CYBER_COMMON_TIME_CONVERSION_H_ diff --git a/cybertron/common/types.h b/cyber/common/types.h similarity index 85% rename from cybertron/common/types.h rename to cyber/common/types.h index f230d9010da..2b6b3f1cc0a 100644 --- a/cybertron/common/types.h +++ b/cyber/common/types.h @@ -14,17 +14,17 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_COMMON_TYPES_H_ -#define CYBERTRON_COMMON_TYPES_H_ +#ifndef CYBER_COMMON_TYPES_H_ +#define CYBER_COMMON_TYPES_H_ #include namespace apollo { -namespace cybertron { +namespace cyber { class NullType {}; -// Return code definition for cybertron internal function return. +// Return code definition for cyber internal function return. enum ReturnCode { SUCC = 0, FAIL = 1, @@ -43,7 +43,7 @@ enum Relation : std::uint8_t { static const char SRV_CHANNEL_REQ_SUFFIX[] = "__SRV__REQUEST"; static const char SRV_CHANNEL_RES_SUFFIX[] = "__SRV__RESPONSE"; -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_COMMON_TYPES_H_ +#endif // CYBER_COMMON_TYPES_H_ diff --git a/cybertron/common/util.h b/cyber/common/util.h similarity index 86% rename from cybertron/common/util.h rename to cyber/common/util.h index 900ca2bb68a..fb9228fd2a0 100644 --- a/cybertron/common/util.h +++ b/cyber/common/util.h @@ -14,13 +14,13 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_COMMON_UTIL_H_ -#define CYBERTRON_COMMON_UTIL_H_ +#ifndef CYBER_COMMON_UTIL_H_ +#define CYBER_COMMON_UTIL_H_ #include namespace apollo { -namespace cybertron { +namespace cyber { namespace common { inline std::size_t Hash(const std::string& key) { @@ -28,7 +28,7 @@ inline std::size_t Hash(const std::string& key) { } } // namespace common -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_COMMON_UTIL_H_ +#endif // CYBER_COMMON_UTIL_H_ diff --git a/cybertron/component/BUILD b/cyber/component/BUILD similarity index 72% rename from cybertron/component/BUILD rename to cyber/component/BUILD index a7eb6b41ad4..3a6b35790cf 100644 --- a/cybertron/component/BUILD +++ b/cyber/component/BUILD @@ -9,7 +9,7 @@ cc_library( ], deps = [ "component_base", - "//cybertron/scheduler:scheduler", + "//cyber/scheduler:scheduler", ], ) @@ -20,7 +20,7 @@ cc_test( "component_test.cc", ], deps = [ - "//cybertron", + "//cyber", "@gtest//:main", ], ) @@ -35,8 +35,8 @@ cc_library( ], deps = [ "component_base", - "//cybertron/blocker:blocker_manager", - "//cybertron/timer:timer", + "//cyber/blocker:blocker_manager", + "//cyber/timer:timer", ], ) @@ -47,7 +47,7 @@ cc_test( "timer_component_test.cc", ], deps = [ - "//cybertron", + "//cyber", "@gtest//:main", ], ) @@ -58,10 +58,10 @@ cc_library( "component_base.h", ], deps = [ - "//cybertron/base:signal", - "//cybertron/base:thread_pool", - "//cybertron/class_loader:class_loader", - "//cybertron/node:node", + "//cyber/base:signal", + "//cyber/base:thread_pool", + "//cyber/class_loader:class_loader", + "//cyber/node:node", ], ) diff --git a/cybertron/component/component.h b/cyber/component/component.h similarity index 95% rename from cybertron/component/component.h rename to cyber/component/component.h index 1eb8a15d143..89c6dca3609 100644 --- a/cybertron/component/component.h +++ b/cyber/component/component.h @@ -14,27 +14,27 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_COMPONENT_COMPONENT_H_ -#define CYBERTRON_COMPONENT_COMPONENT_H_ +#ifndef CYBER_COMPONENT_COMPONENT_H_ +#define CYBER_COMPONENT_COMPONENT_H_ #include #include #include -#include "cybertron/blocker/blocker_manager.h" -#include "cybertron/common/global_data.h" -#include "cybertron/common/types.h" -#include "cybertron/common/util.h" -#include "cybertron/component/component_base.h" -#include "cybertron/croutine/routine_factory.h" -#include "cybertron/data/data_visitor.h" -#include "cybertron/scheduler/scheduler.h" +#include "cyber/blocker/blocker_manager.h" +#include "cyber/common/global_data.h" +#include "cyber/common/types.h" +#include "cyber/common/util.h" +#include "cyber/component/component_base.h" +#include "cyber/croutine/routine_factory.h" +#include "cyber/data/data_visitor.h" +#include "cyber/scheduler/scheduler.h" namespace apollo { -namespace cybertron { +namespace cyber { -using apollo::cybertron::common::GlobalData; -using apollo::cybertron::proto::RoleAttributes; +using apollo::cyber::common::GlobalData; +using apollo::cyber::proto::RoleAttributes; template @@ -515,10 +515,10 @@ bool Component::Initialize(const ComponentConfig& config) { return sched->CreateTask(factory, node_->Name()); } -#define CYBERTRON_REGISTER_COMPONENT(name) \ - CLASS_LOADER_REGISTER_CLASS(name, apollo::cybertron::ComponentBase) +#define CYBER_REGISTER_COMPONENT(name) \ + CLASS_LOADER_REGISTER_CLASS(name, apollo::cyber::ComponentBase) -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_COMPONENT_COMPONENT_H_ +#endif // CYBER_COMPONENT_COMPONENT_H_ diff --git a/cybertron/component/component_base.h b/cyber/component/component_base.h similarity index 85% rename from cybertron/component/component_base.h rename to cyber/component/component_base.h index c5acbcf83ff..a68602a7cd2 100644 --- a/cybertron/component/component_base.h +++ b/cyber/component/component_base.h @@ -14,31 +14,31 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_COMPONENT_COMPONENT_BASE_H_ -#define CYBERTRON_COMPONENT_COMPONENT_BASE_H_ +#ifndef CYBER_COMPONENT_COMPONENT_BASE_H_ +#define CYBER_COMPONENT_COMPONENT_BASE_H_ #include #include #include #include -#include "cybertron/class_loader/class_loader.h" -#include "cybertron/common/environment.h" -#include "cybertron/common/file.h" -#include "cybertron/node/node.h" -#include "cybertron/proto/component_config.pb.h" +#include "cyber/class_loader/class_loader.h" +#include "cyber/common/environment.h" +#include "cyber/common/file.h" +#include "cyber/node/node.h" +#include "cyber/proto/component_config.pb.h" #include "gflags/gflags.h" namespace apollo { -namespace cybertron { +namespace cyber { -using apollo::cybertron::proto::ComponentConfig; -using apollo::cybertron::proto::TimerComponentConfig; +using apollo::cyber::proto::ComponentConfig; +using apollo::cyber::proto::TimerComponentConfig; class ComponentBase : public std::enable_shared_from_this { public: template - using Reader = cybertron::Reader; + using Reader = cyber::Reader; virtual ~ComponentBase() {} @@ -101,7 +101,7 @@ class ComponentBase : public std::enable_shared_from_this { std::vector> readers_; }; -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_COMPONENT_COMPONENT_BASE_H_ +#endif // CYBER_COMPONENT_COMPONENT_BASE_H_ diff --git a/cybertron/component/component_test.cc b/cyber/component/component_test.cc similarity index 80% rename from cybertron/component/component_test.cc rename to cyber/component/component_test.cc index 3f1cf95722b..64e6e0694bb 100644 --- a/cybertron/component/component_test.cc +++ b/cyber/component/component_test.cc @@ -17,17 +17,17 @@ #include #include -#include "cybertron/component/component.h" -#include "cybertron/init.h" -#include "cybertron/message/raw_message.h" +#include "cyber/component/component.h" +#include "cyber/init.h" +#include "cyber/message/raw_message.h" namespace apollo { -namespace cybertron { +namespace cyber { -using apollo::cybertron::Component; -using apollo::cybertron::message::RawMessage; -using apollo::cybertron::proto::ComponentConfig; -using apollo::cybertron::proto::TimerComponentConfig; +using apollo::cyber::Component; +using apollo::cyber::message::RawMessage; +using apollo::cyber::proto::ComponentConfig; +using apollo::cyber::proto::TimerComponentConfig; static bool ret_proc = true; static bool ret_init = true; template { TEST(TimerComponent, init) { ret_proc = true; ret_init = true; - apollo::cybertron::proto::ComponentConfig compcfg; + apollo::cyber::proto::ComponentConfig compcfg; auto msg_str1 = std::make_shared(); auto msg_str2 = std::make_shared(); auto msg_str3 = std::make_shared(); auto msg_str4 = std::make_shared(); compcfg.set_name("perception"); - apollo::cybertron::proto::ReaderOption *read_opt = compcfg.add_readers(); + apollo::cyber::proto::ReaderOption *read_opt = compcfg.add_readers(); read_opt->set_channel("/perception/channel"); auto comC = std::make_shared>(); EXPECT_EQ(true, comC->Initialize(compcfg)); EXPECT_EQ(true, comC->Process(msg_str1)); compcfg.set_name("perception2"); - apollo::cybertron::proto::ReaderOption *read_opt2 = compcfg.add_readers(); + apollo::cyber::proto::ReaderOption *read_opt2 = compcfg.add_readers(); read_opt2->set_channel("/driver/channel1"); auto comB = std::make_shared>(); EXPECT_EQ(true, comB->Initialize(compcfg)); EXPECT_EQ(true, comB->Process(msg_str1, msg_str2)); compcfg.set_name("perception3"); - apollo::cybertron::proto::ReaderOption *read_opt3 = compcfg.add_readers(); + apollo::cyber::proto::ReaderOption *read_opt3 = compcfg.add_readers(); read_opt3->set_channel("/driver/channel2"); compcfg.set_name("perception4"); - apollo::cybertron::proto::ReaderOption *read_opt4 = compcfg.add_readers(); + apollo::cyber::proto::ReaderOption *read_opt4 = compcfg.add_readers(); read_opt4->set_channel("/driver/channel3"); auto comA = std::make_shared< Component_A>(); @@ -104,7 +104,7 @@ TEST(TimerComponent, init) { TEST(TimerComponentFail, init) { ret_proc = false; ret_init = false; - apollo::cybertron::proto::ComponentConfig compcfg; + apollo::cyber::proto::ComponentConfig compcfg; auto msg_str1 = std::make_shared(); auto msg_str2 = std::make_shared(); @@ -112,21 +112,21 @@ TEST(TimerComponentFail, init) { auto msg_str4 = std::make_shared(); compcfg.set_name("perception_f"); - apollo::cybertron::proto::ReaderOption *read_opt = compcfg.add_readers(); + apollo::cyber::proto::ReaderOption *read_opt = compcfg.add_readers(); read_opt->set_channel("/perception/channel"); auto comC = std::make_shared>(); EXPECT_EQ(false, comC->Initialize(compcfg)); EXPECT_EQ(false, comC->Process(msg_str1)); compcfg.set_name("perception2_f"); - apollo::cybertron::proto::ReaderOption *read_opt2 = compcfg.add_readers(); + apollo::cyber::proto::ReaderOption *read_opt2 = compcfg.add_readers(); read_opt2->set_channel("/driver/channel"); auto comB = std::make_shared>(); EXPECT_EQ(false, comB->Initialize(compcfg)); EXPECT_EQ(false, comB->Process(msg_str1, msg_str2)); compcfg.set_name("perception3_F"); - apollo::cybertron::proto::ReaderOption *read_opt3 = compcfg.add_readers(); + apollo::cyber::proto::ReaderOption *read_opt3 = compcfg.add_readers(); read_opt3->set_channel("/driver/channel"); auto comA = std::make_shared< Component_A>(); @@ -134,5 +134,5 @@ TEST(TimerComponentFail, init) { EXPECT_EQ(false, comA->Process(msg_str1, msg_str2, msg_str3, msg_str4)); } -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/component/timer_component.cc b/cyber/component/timer_component.cc similarity index 92% rename from cybertron/component/timer_component.cc rename to cyber/component/timer_component.cc index 7862b7fec98..0d3637ae423 100644 --- a/cybertron/component/timer_component.cc +++ b/cyber/component/timer_component.cc @@ -14,11 +14,11 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/component/timer_component.h" -#include "cybertron/timer/timer.h" +#include "cyber/component/timer_component.h" +#include "cyber/timer/timer.h" namespace apollo { -namespace cybertron { +namespace cyber { TimerComponent::TimerComponent() {} @@ -56,5 +56,5 @@ bool TimerComponent::Initialize(const TimerComponentConfig& config) { return true; } -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/component/timer_component.h b/cyber/component/timer_component.h similarity index 83% rename from cybertron/component/timer_component.h rename to cyber/component/timer_component.h index 52dc35093a2..b5f267fc39e 100644 --- a/cybertron/component/timer_component.h +++ b/cyber/component/timer_component.h @@ -14,15 +14,15 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_COMPONENT_TIMER_COMPONENT_H_ -#define CYBERTRON_COMPONENT_TIMER_COMPONENT_H_ +#ifndef CYBER_COMPONENT_TIMER_COMPONENT_H_ +#define CYBER_COMPONENT_TIMER_COMPONENT_H_ #include -#include "cybertron/component/component_base.h" +#include "cyber/component/component_base.h" namespace apollo { -namespace cybertron { +namespace cyber { class Timer; @@ -45,7 +45,7 @@ class TimerComponent : public ComponentBase { std::unique_ptr timer_; }; -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_COMPONENT_TIMER_COMPONENT_H_ +#endif // CYBER_COMPONENT_TIMER_COMPONENT_H_ diff --git a/cybertron/component/timer_component_test.cc b/cyber/component/timer_component_test.cc similarity index 87% rename from cybertron/component/timer_component_test.cc rename to cyber/component/timer_component_test.cc index 35a396b206f..21f2fda14e2 100644 --- a/cybertron/component/timer_component_test.cc +++ b/cyber/component/timer_component_test.cc @@ -17,11 +17,11 @@ #include #include -#include "cybertron/component/timer_component.h" -#include "cybertron/init.h" +#include "cyber/component/timer_component.h" +#include "cyber/init.h" namespace apollo { -namespace cybertron { +namespace cyber { static bool ret_proc = true; static bool ret_init = true; @@ -36,7 +36,7 @@ class Component_Timer : public TimerComponent { TEST(TimerComponent, timertest) { ret_proc = true; ret_init = true; - apollo::cybertron::proto::TimerComponentConfig compcfg; + apollo::cyber::proto::TimerComponentConfig compcfg; compcfg.set_name("driver"); compcfg.set_interval(100); @@ -48,7 +48,7 @@ TEST(TimerComponent, timertest) { TEST(TimerComponentFalse, timerfail) { ret_proc = false; ret_init = false; - apollo::cybertron::proto::TimerComponentConfig compcfg; + apollo::cyber::proto::TimerComponentConfig compcfg; compcfg.set_name("driver1"); compcfg.set_interval(100); @@ -56,5 +56,5 @@ TEST(TimerComponentFalse, timerfail) { EXPECT_EQ(false, com->Initialize(compcfg)); EXPECT_EQ(false, com->Process()); } -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/conf/benchmark_dag_config.pb.conf b/cyber/conf/benchmark_dag_config.pb.conf similarity index 100% rename from cybertron/conf/benchmark_dag_config.pb.conf rename to cyber/conf/benchmark_dag_config.pb.conf diff --git a/cybertron/conf/cybertron.pb.conf b/cyber/conf/cyber.pb.conf similarity index 100% rename from cybertron/conf/cybertron.pb.conf rename to cyber/conf/cyber.pb.conf diff --git a/cybertron/croutine/BUILD b/cyber/croutine/BUILD similarity index 54% rename from cybertron/croutine/BUILD rename to cyber/croutine/BUILD index 682e974c64b..82c716140f4 100644 --- a/cybertron/croutine/BUILD +++ b/cyber/croutine/BUILD @@ -11,18 +11,18 @@ cc_library( "croutine.h", ], deps = [ - "//cybertron:init", - "//cybertron/base:atomic_hash_map", - "//cybertron/base:atomic_rw_lock", - "//cybertron/base:bounded_queue", - "//cybertron/base:macros", - "//cybertron/base:wait_strategy", - "//cybertron/common:common", - "//cybertron/event:perf_event_cache", - "//cybertron/time:time", - "//cybertron/croutine:routine_context", - "//cybertron/croutine:routine_factory", - "//cybertron/croutine:swap", + "//cyber:init", + "//cyber/base:atomic_hash_map", + "//cyber/base:atomic_rw_lock", + "//cyber/base:bounded_queue", + "//cyber/base:macros", + "//cyber/base:wait_strategy", + "//cyber/common:common", + "//cyber/event:perf_event_cache", + "//cyber/time:time", + "//cyber/croutine:routine_context", + "//cyber/croutine:routine_factory", + "//cyber/croutine:swap", ], ) @@ -35,7 +35,7 @@ cc_library( "routine_context.h", ], deps = [ - "//cybertron/common:common", + "//cyber/common:common", ], ) @@ -45,8 +45,8 @@ cc_library( "routine_factory.h", ], deps = [ - "//cybertron/common:common", - "//cybertron/event:perf_event_cache", + "//cyber/common:common", + "//cyber/event:perf_event_cache", ], ) @@ -64,7 +64,7 @@ cc_test( "croutine_test.cc", ], deps = [ - "//cybertron", + "//cyber", "@gtest//:main", ], ) diff --git a/cybertron/croutine/croutine.cc b/cyber/croutine/croutine.cc similarity index 85% rename from cybertron/croutine/croutine.cc rename to cyber/croutine/croutine.cc index 4d9fde269ac..d7d022e1029 100644 --- a/cybertron/croutine/croutine.cc +++ b/cyber/croutine/croutine.cc @@ -14,21 +14,21 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/croutine/croutine.h" +#include "cyber/croutine/croutine.h" #include -#include "cybertron/common/log.h" -#include "cybertron/croutine/routine_context.h" -#include "cybertron/event/perf_event_cache.h" -#include "cybertron/time/time.h" +#include "cyber/common/log.h" +#include "cyber/croutine/routine_context.h" +#include "cyber/event/perf_event_cache.h" +#include "cyber/time/time.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace croutine { -using apollo::cybertron::event::PerfEventCache; -using apollo::cybertron::event::SchedPerf; +using apollo::cyber::event::PerfEventCache; +using apollo::cyber::event::SchedPerf; thread_local CRoutine *CRoutine::current_routine_; thread_local std::shared_ptr CRoutine::main_context_; @@ -70,11 +70,11 @@ RoutineState CRoutine::Resume() { current_routine_ = this; } - auto t_start = cybertron::Time::Now().ToNanosecond(); + auto t_start = cyber::Time::Now().ToNanosecond(); PerfEventCache::Instance()->AddSchedEvent(SchedPerf::SWAP_IN, id_, processor_id_, 0, 0, -1, -1); SwapContext(GetMainContext(), this->GetContext()); - auto t_end = cybertron::Time::Now().ToNanosecond(); + auto t_end = cyber::Time::Now().ToNanosecond(); PerfEventCache::Instance()->AddSchedEvent(SchedPerf::SWAP_OUT, id_, processor_id_, 0, t_start, -1, static_cast(state_)); @@ -96,5 +96,5 @@ void CRoutine::Routine() { void CRoutine::Stop() { force_stop_ = true; } } // namespace croutine -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/croutine/croutine.h b/cyber/croutine/croutine.h similarity index 97% rename from cybertron/croutine/croutine.h rename to cyber/croutine/croutine.h index 898bd8ab5cb..78b123506c2 100644 --- a/cybertron/croutine/croutine.h +++ b/cyber/croutine/croutine.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_CROUTINE_CROUTINE_H_ -#define CYBERTRON_CROUTINE_CROUTINE_H_ +#ifndef CYBER_CROUTINE_CROUTINE_H_ +#define CYBER_CROUTINE_CROUTINE_H_ #include #include @@ -24,10 +24,10 @@ #include #include -#include "cybertron/croutine/routine_context.h" +#include "cyber/croutine/routine_context.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace croutine { using RoutineFunc = std::function; @@ -260,7 +260,7 @@ inline void CRoutine::Unlock() { } } // namespace croutine -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_CROUTINE_CROUTINE_H_ +#endif // CYBER_CROUTINE_CROUTINE_H_ diff --git a/cybertron/croutine/croutine_test.cc b/cyber/croutine/croutine_test.cc similarity index 76% rename from cybertron/croutine/croutine_test.cc rename to cyber/croutine/croutine_test.cc index 253726765d2..d319ccc1910 100644 --- a/cybertron/croutine/croutine_test.cc +++ b/cyber/croutine/croutine_test.cc @@ -17,13 +17,13 @@ #include #include -#include "cybertron/croutine/croutine.h" -#include "cybertron/croutine/routine_context.h" -#include "cybertron/cybertron.h" +#include "cyber/croutine/croutine.h" +#include "cyber/croutine/routine_context.h" +#include "cyber/cyber.h" #include "gtest/gtest.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace croutine { void Sleep(uint64_t ms) { @@ -32,13 +32,13 @@ void Sleep(uint64_t ms) { class ParameterServerTest : public ::testing::Test { virtual void SetUp() { - apollo::cybertron::Init(); + apollo::cyber::Init(); auto context = - std::make_shared(); - apollo::cybertron::croutine::CRoutine::SetMainContext(context); + std::make_shared(); + apollo::cyber::croutine::CRoutine::SetMainContext(context); } }; } // namespace croutine -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/croutine/routine_context.cc b/cyber/croutine/routine_context.cc similarity index 93% rename from cybertron/croutine/routine_context.cc rename to cyber/croutine/routine_context.cc index 1705e1ae088..d9793dc75a6 100644 --- a/cybertron/croutine/routine_context.cc +++ b/cyber/croutine/routine_context.cc @@ -14,10 +14,10 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/croutine/routine_context.h" +#include "cyber/croutine/routine_context.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace croutine { void MakeContext(const func &f1, const void *arg, RoutineContext *ctx) { @@ -31,5 +31,5 @@ void MakeContext(const func &f1, const void *arg, RoutineContext *ctx) { } } // namespace croutine -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/croutine/routine_context.h b/cyber/croutine/routine_context.h similarity index 86% rename from cybertron/croutine/routine_context.h rename to cyber/croutine/routine_context.h index 5490afcd8ff..74134790181 100644 --- a/cybertron/croutine/routine_context.h +++ b/cyber/croutine/routine_context.h @@ -14,20 +14,20 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_CROUTINE_ROUTINE_CONTEXT_H_ -#define CYBERTRON_CROUTINE_ROUTINE_CONTEXT_H_ +#ifndef CYBER_CROUTINE_ROUTINE_CONTEXT_H_ +#define CYBER_CROUTINE_ROUTINE_CONTEXT_H_ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" extern "C" { extern void ctx_swap(void**, void**) asm("ctx_swap"); }; namespace apollo { -namespace cybertron { +namespace cyber { namespace croutine { static const int STACK_SIZE = 8 * 1024 * 1024; @@ -48,7 +48,7 @@ inline void SwapContext(RoutineContext* src_ctx, RoutineContext* dst_ctx) { } } // namespace croutine -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_CROUTINE_ROUTINE_CONTEXT_H_ +#endif // CYBER_CROUTINE_ROUTINE_CONTEXT_H_ diff --git a/cybertron/croutine/routine_factory.h b/cyber/croutine/routine_factory.h similarity index 92% rename from cybertron/croutine/routine_factory.h rename to cyber/croutine/routine_factory.h index 6375811eb76..8dc4ee63d5c 100644 --- a/cybertron/croutine/routine_factory.h +++ b/cyber/croutine/routine_factory.h @@ -15,25 +15,25 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_CROUTINE_ROUTINE_FACTORY_H_ -#define CYBERTRON_CROUTINE_ROUTINE_FACTORY_H_ +#ifndef CYBER_CROUTINE_ROUTINE_FACTORY_H_ +#define CYBER_CROUTINE_ROUTINE_FACTORY_H_ #include #include -#include "cybertron/common/global_data.h" -#include "cybertron/common/log.h" -#include "cybertron/croutine/croutine.h" -#include "cybertron/data/data_visitor.h" -#include "cybertron/event/perf_event_cache.h" +#include "cyber/common/global_data.h" +#include "cyber/common/log.h" +#include "cyber/croutine/croutine.h" +#include "cyber/data/data_visitor.h" +#include "cyber/event/perf_event_cache.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace croutine { using common::GlobalData; -using apollo::cybertron::event::PerfEventCache; -using apollo::cybertron::event::SchedPerf; +using apollo::cyber::event::PerfEventCache; +using apollo::cyber::event::SchedPerf; class RoutineFactory { public: @@ -175,7 +175,7 @@ RoutineFactory CreateRoutineFactory(Function&& f) { } } // namespace croutine -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_CROUTINE_ROUTINE_FACTORY_H_ +#endif // CYBER_CROUTINE_ROUTINE_FACTORY_H_ diff --git a/cybertron/croutine/swap.S b/cyber/croutine/swap.S similarity index 100% rename from cybertron/croutine/swap.S rename to cyber/croutine/swap.S diff --git a/cybertron/cybertron.cc b/cyber/cyber.cc similarity index 80% rename from cybertron/cybertron.cc rename to cyber/cyber.cc index 444c380688c..9535910fbc0 100644 --- a/cybertron/cybertron.cc +++ b/cyber/cyber.cc @@ -14,32 +14,32 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include #include #include -#include "cybertron/common/global_data.h" -#include "cybertron/proto/run_mode_conf.pb.h" +#include "cyber/common/global_data.h" +#include "cyber/proto/run_mode_conf.pb.h" namespace apollo { -namespace cybertron { +namespace cyber { -using apollo::cybertron::common::GlobalData; -using apollo::cybertron::proto::RunMode; +using apollo::cyber::common::GlobalData; +using apollo::cyber::proto::RunMode; std::unique_ptr CreateNode(const std::string& node_name, const std::string& name_space) { bool is_reality_mode = GlobalData::Instance()->IsRealityMode(); if (is_reality_mode && !OK()) { // add some hint log - AERROR << "please initialize cybertron firstly."; + AERROR << "please initialize cyber firstly."; return nullptr; } std::unique_ptr node(new Node(node_name, name_space)); return std::move(node); } -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/cybertron.h b/cyber/cyber.h similarity index 72% rename from cybertron/cybertron.h rename to cyber/cyber.h index d02f4c87267..3ca1140506b 100644 --- a/cybertron/cybertron.h +++ b/cyber/cyber.h @@ -14,28 +14,28 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_CYBERTRON_H_ -#define CYBERTRON_CYBERTRON_H_ +#ifndef CYBER_CYBER_H_ +#define CYBER_CYBER_H_ #include #include #include -#include "cybertron/common/log.h" -#include "cybertron/component/component.h" -#include "cybertron/init.h" -#include "cybertron/node/node.h" -#include "cybertron/task/task.h" -#include "cybertron/time/time.h" -#include "cybertron/timer/timer.h" +#include "cyber/common/log.h" +#include "cyber/component/component.h" +#include "cyber/init.h" +#include "cyber/node/node.h" +#include "cyber/task/task.h" +#include "cyber/time/time.h" +#include "cyber/timer/timer.h" namespace apollo { -namespace cybertron { +namespace cyber { std::unique_ptr CreateNode(const std::string& node_name, const std::string& name_space = ""); -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_CYBERTRON_H_ +#endif // CYBER_CYBER_H_ diff --git a/cybertron/data/BUILD b/cyber/data/BUILD similarity index 96% rename from cybertron/data/BUILD rename to cyber/data/BUILD index a1239e453a1..5f4a8a15f9d 100644 --- a/cybertron/data/BUILD +++ b/cyber/data/BUILD @@ -69,7 +69,7 @@ cc_test( "data_visitor_test.cc", ], deps = [ - "//cybertron", + "//cyber", "@gtest//:main", ], ) @@ -99,7 +99,7 @@ cc_test( "data_dispatcher_test.cc", ], deps = [ - "//cybertron", + "//cyber", "@gtest//:main", ], ) @@ -111,7 +111,7 @@ cc_test( "channel_buffer_test.cc", ], deps = [ - "//cybertron", + "//cyber", "@gtest//:main", ], ) diff --git a/cybertron/data/cache_buffer.h b/cyber/data/cache_buffer.h similarity index 93% rename from cybertron/data/cache_buffer.h rename to cyber/data/cache_buffer.h index 43bc17afe95..25419787f6a 100644 --- a/cybertron/data/cache_buffer.h +++ b/cyber/data/cache_buffer.h @@ -14,14 +14,14 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_DATA_CACHE_BUFFER_H_ -#define CYBERTRON_DATA_CACHE_BUFFER_H_ +#ifndef CYBER_DATA_CACHE_BUFFER_H_ +#define CYBER_DATA_CACHE_BUFFER_H_ #include #include namespace apollo { -namespace cybertron { +namespace cyber { namespace data { template @@ -81,7 +81,7 @@ class CacheBuffer { }; } // namespace data -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_DATA_CACHE_BUFFER_H_ +#endif // CYBER_DATA_CACHE_BUFFER_H_ diff --git a/cybertron/data/cache_buffer_test.cc b/cyber/data/cache_buffer_test.cc similarity index 94% rename from cybertron/data/cache_buffer_test.cc rename to cyber/data/cache_buffer_test.cc index 7caa5153694..baa8420290a 100644 --- a/cybertron/data/cache_buffer_test.cc +++ b/cyber/data/cache_buffer_test.cc @@ -19,10 +19,10 @@ #include #include -#include "cybertron/data/cache_buffer.h" +#include "cyber/data/cache_buffer.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace data { TEST(CacheBufferTest, cache_buffer_test) { @@ -46,5 +46,5 @@ TEST(CacheBufferTest, cache_buffer_test) { } } // namespace data -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/data/channel_buffer.h b/cyber/data/channel_buffer.h similarity index 88% rename from cybertron/data/channel_buffer.h rename to cyber/data/channel_buffer.h index 6643bad623e..9610b53a317 100644 --- a/cybertron/data/channel_buffer.h +++ b/cyber/data/channel_buffer.h @@ -14,24 +14,24 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_DATA_CHANNEL_BUFFER_H_ -#define CYBERTRON_DATA_CHANNEL_BUFFER_H_ +#ifndef CYBER_DATA_CHANNEL_BUFFER_H_ +#define CYBER_DATA_CHANNEL_BUFFER_H_ #include #include #include #include -#include "cybertron/common/global_data.h" -#include "cybertron/common/log.h" -#include "cybertron/data/data_notifier.h" -#include "cybertron/proto/component_config.pb.h" +#include "cyber/common/global_data.h" +#include "cyber/common/log.h" +#include "cyber/data/data_notifier.h" +#include "cyber/proto/component_config.pb.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace data { -using apollo::cybertron::common::GlobalData; +using apollo::cyber::common::GlobalData; template class ChannelBuffer { @@ -106,7 +106,7 @@ bool ChannelBuffer::FetchMulti(uint64_t fetch_size, } } // namespace data -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_DATA_CHANNEL_BUFFER_H_ +#endif // CYBER_DATA_CHANNEL_BUFFER_H_ diff --git a/cybertron/data/channel_buffer_test.cc b/cyber/data/channel_buffer_test.cc similarity index 96% rename from cybertron/data/channel_buffer_test.cc rename to cyber/data/channel_buffer_test.cc index be6effbaa91..55c6a7cb9af 100644 --- a/cybertron/data/channel_buffer_test.cc +++ b/cyber/data/channel_buffer_test.cc @@ -18,11 +18,11 @@ #include #include "gtest/gtest.h" -#include "cybertron/common/util.h" -#include "cybertron/data/channel_buffer.h" +#include "cyber/common/util.h" +#include "cyber/data/channel_buffer.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace data { auto channel0 = common::Hash("/channel0"); @@ -97,5 +97,5 @@ TEST(ChannelBufferTest, FetchMulti) { } } // namespace data -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/data/data_dispatcher.h b/cyber/data/data_dispatcher.h similarity index 83% rename from cybertron/data/data_dispatcher.h rename to cyber/data/data_dispatcher.h index 23dcaf6c066..5f9e5b27481 100644 --- a/cybertron/data/data_dispatcher.h +++ b/cyber/data/data_dispatcher.h @@ -14,25 +14,25 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_DATA_DATA_DISPATCHER_H_ -#define CYBERTRON_DATA_DATA_DISPATCHER_H_ +#ifndef CYBER_DATA_DATA_DISPATCHER_H_ +#define CYBER_DATA_DATA_DISPATCHER_H_ #include #include #include -#include "cybertron/common/log.h" -#include "cybertron/common/macros.h" -#include "cybertron/data/channel_buffer.h" -#include "cybertron/init.h" -#include "cybertron/time/time.h" +#include "cyber/common/log.h" +#include "cyber/common/macros.h" +#include "cyber/data/channel_buffer.h" +#include "cyber/init.h" +#include "cyber/time/time.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace data { -using apollo::cybertron::Time; -using apollo::cybertron::base::AtomicHashMap; +using apollo::cyber::Time; +using apollo::cyber::base::AtomicHashMap; template class DataDispatcher { @@ -73,7 +73,7 @@ template bool DataDispatcher::Dispatch(const uint64_t channel_id, const std::shared_ptr& msg) { BufferVector* buffers = nullptr; - if (apollo::cybertron::IsShutdown()) { + if (apollo::cyber::IsShutdown()) { return false; } if (buffers_map_.Get(channel_id, &buffers)) { @@ -90,7 +90,7 @@ bool DataDispatcher::Dispatch(const uint64_t channel_id, } } // namespace data -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_DATA_DATA_DISPATCHER_H_ +#endif // CYBER_DATA_DATA_DISPATCHER_H_ diff --git a/cybertron/data/data_dispatcher_test.cc b/cyber/data/data_dispatcher_test.cc similarity index 94% rename from cybertron/data/data_dispatcher_test.cc rename to cyber/data/data_dispatcher_test.cc index ba612840ac1..f35fc1fc9c8 100644 --- a/cybertron/data/data_dispatcher_test.cc +++ b/cyber/data/data_dispatcher_test.cc @@ -18,11 +18,11 @@ #include #include -#include "cybertron/common/util.h" -#include "cybertron/data/data_dispatcher.h" +#include "cyber/common/util.h" +#include "cyber/data/data_dispatcher.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace data { template @@ -57,5 +57,5 @@ TEST(DataDispatcher, Dispatch) { } } // namespace data -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/data/data_notifier.h b/cyber/data/data_notifier.h similarity index 81% rename from cybertron/data/data_notifier.h rename to cyber/data/data_notifier.h index 5dbe535f251..14cbcd1b8fa 100644 --- a/cybertron/data/data_notifier.h +++ b/cyber/data/data_notifier.h @@ -14,26 +14,26 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_DATA_DATA_NOTIFIER_H_ -#define CYBERTRON_DATA_DATA_NOTIFIER_H_ +#ifndef CYBER_DATA_DATA_NOTIFIER_H_ +#define CYBER_DATA_DATA_NOTIFIER_H_ #include #include #include -#include "cybertron/common/log.h" -#include "cybertron/common/macros.h" -#include "cybertron/data/cache_buffer.h" -#include "cybertron/event/perf_event_cache.h" -#include "cybertron/time/time.h" +#include "cyber/common/log.h" +#include "cyber/common/macros.h" +#include "cyber/data/cache_buffer.h" +#include "cyber/event/perf_event_cache.h" +#include "cyber/time/time.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace data { -using apollo::cybertron::Time; -using apollo::cybertron::base::AtomicHashMap; -using apollo::cybertron::event::PerfEventCache; +using apollo::cyber::Time; +using apollo::cyber::base::AtomicHashMap; +using apollo::cyber::event::PerfEventCache; struct Notifier { std::function callback; @@ -84,7 +84,7 @@ inline bool DataNotifier::Notify(const uint64_t channel_id) { } } // namespace data -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_DATA_DATA_NOTIFIER_H_ +#endif // CYBER_DATA_DATA_NOTIFIER_H_ diff --git a/cybertron/data/data_visitor.h b/cyber/data/data_visitor.h similarity index 93% rename from cybertron/data/data_visitor.h rename to cyber/data/data_visitor.h index 7302778b402..4633411bf03 100644 --- a/cybertron/data/data_visitor.h +++ b/cyber/data/data_visitor.h @@ -14,23 +14,23 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_DATA_DATA_VISITOR_H_ -#define CYBERTRON_DATA_DATA_VISITOR_H_ +#ifndef CYBER_DATA_DATA_VISITOR_H_ +#define CYBER_DATA_DATA_VISITOR_H_ #include #include #include #include -#include "cybertron/common/log.h" -#include "cybertron/data/channel_buffer.h" -#include "cybertron/data/data_dispatcher.h" -#include "cybertron/data/data_visitor_base.h" -#include "cybertron/data/fusion/all_latest.h" -#include "cybertron/data/fusion/data_fusion.h" +#include "cyber/common/log.h" +#include "cyber/data/channel_buffer.h" +#include "cyber/data/data_dispatcher.h" +#include "cyber/data/data_visitor_base.h" +#include "cyber/data/fusion/all_latest.h" +#include "cyber/data/fusion/data_fusion.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace data { struct VisitorConfig { @@ -184,7 +184,7 @@ class DataVisitor : public DataVisitorBase { }; } // namespace data -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_DATA_DATA_VISITOR_H_ +#endif // CYBER_DATA_DATA_VISITOR_H_ diff --git a/cybertron/data/data_visitor_base.h b/cyber/data/data_visitor_base.h similarity index 80% rename from cybertron/data/data_visitor_base.h rename to cyber/data/data_visitor_base.h index 29a4ce5f788..87890e95d60 100644 --- a/cybertron/data/data_visitor_base.h +++ b/cyber/data/data_visitor_base.h @@ -14,21 +14,21 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_DATA_DATA_VISITOR_BASE_H_ -#define CYBERTRON_DATA_DATA_VISITOR_BASE_H_ +#ifndef CYBER_DATA_DATA_VISITOR_BASE_H_ +#define CYBER_DATA_DATA_VISITOR_BASE_H_ #include #include #include #include -#include "cybertron/common/global_data.h" -#include "cybertron/common/log.h" -#include "cybertron/data/data_notifier.h" -#include "cybertron/proto/component_config.pb.h" +#include "cyber/common/global_data.h" +#include "cyber/common/log.h" +#include "cyber/data/data_notifier.h" +#include "cyber/proto/component_config.pb.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace data { class DataVisitorBase { @@ -49,7 +49,7 @@ class DataVisitorBase { }; } // namespace data -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_DATA_DATA_VISITOR_BASE_H_ +#endif // CYBER_DATA_DATA_VISITOR_BASE_H_ diff --git a/cybertron/data/data_visitor_test.cc b/cyber/data/data_visitor_test.cc similarity index 93% rename from cybertron/data/data_visitor_test.cc rename to cyber/data/data_visitor_test.cc index 8bde614942e..0eccec8734c 100644 --- a/cybertron/data/data_visitor_test.cc +++ b/cyber/data/data_visitor_test.cc @@ -19,17 +19,17 @@ #include #include -#include "cybertron/common/log.h" -#include "cybertron/cybertron.h" -#include "cybertron/data/data_visitor.h" -#include "cybertron/message/raw_message.h" +#include "cyber/common/log.h" +#include "cyber/cyber.h" +#include "cyber/data/data_visitor.h" +#include "cyber/message/raw_message.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace data { -using apollo::cybertron::message::RawMessage; -using apollo::cybertron::proto::RoleAttributes; +using apollo::cyber::message::RawMessage; +using apollo::cyber::proto::RoleAttributes; std::hash str_hash; auto channel0 = str_hash("/channel0"); @@ -131,5 +131,5 @@ TEST(DataVisitorTest, four_channel) { } } // namespace data -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/data/fusion/all_latest.h b/cyber/data/fusion/all_latest.h similarity index 91% rename from cybertron/data/fusion/all_latest.h rename to cyber/data/fusion/all_latest.h index deda7fc9977..31c23e84d84 100644 --- a/cybertron/data/fusion/all_latest.h +++ b/cyber/data/fusion/all_latest.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_DATA_FUSION_ALL_LATEST_H_ -#define CYBERTRON_DATA_FUSION_ALL_LATEST_H_ +#ifndef CYBER_DATA_FUSION_ALL_LATEST_H_ +#define CYBER_DATA_FUSION_ALL_LATEST_H_ #include #include @@ -24,12 +24,12 @@ #include #include -#include "cybertron/common/types.h" -#include "cybertron/data/channel_buffer.h" -#include "cybertron/data/fusion/data_fusion.h" +#include "cyber/common/types.h" +#include "cyber/data/channel_buffer.h" +#include "cyber/data/fusion/data_fusion.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace data { namespace fusion { @@ -97,7 +97,7 @@ class AllLatest : public DataFusion { } // namespace fusion } // namespace data -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_DATA_FUSION_ALL_LATEST_H_ +#endif // CYBER_DATA_FUSION_ALL_LATEST_H_ diff --git a/cybertron/data/fusion/data_fusion.h b/cyber/data/fusion/data_fusion.h similarity index 90% rename from cybertron/data/fusion/data_fusion.h rename to cyber/data/fusion/data_fusion.h index 8dc5fc7bf03..e391c1d4f99 100644 --- a/cybertron/data/fusion/data_fusion.h +++ b/cyber/data/fusion/data_fusion.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_DATA_FUSION_DATA_FUSION_H_ -#define CYBERTRON_DATA_FUSION_DATA_FUSION_H_ +#ifndef CYBER_DATA_FUSION_DATA_FUSION_H_ +#define CYBER_DATA_FUSION_DATA_FUSION_H_ #include #include @@ -24,10 +24,10 @@ #include #include -#include "cybertron/common/types.h" +#include "cyber/common/types.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace data { namespace fusion { @@ -63,7 +63,7 @@ class DataFusion { } // namespace fusion } // namespace data -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_DATA_FUSION_DATA_FUSION_H_ +#endif // CYBER_DATA_FUSION_DATA_FUSION_H_ diff --git a/cybertron/event/BUILD b/cyber/event/BUILD similarity index 64% rename from cybertron/event/BUILD rename to cyber/event/BUILD index 052edd35872..8f4ac43ed6d 100644 --- a/cybertron/event/BUILD +++ b/cyber/event/BUILD @@ -11,8 +11,8 @@ cc_library( "perf_event.h", ], deps = [ - "//cybertron/base:bounded_queue", - "//cybertron/common", + "//cyber/base:bounded_queue", + "//cyber/common", ], ) @@ -25,10 +25,10 @@ cc_library( "perf_event_cache.h", ], deps = [ - "//cybertron:init", - "//cybertron/event:perf_event", - "//cybertron/proto:perf_conf_cc_proto", - "//cybertron/time:time", + "//cyber:init", + "//cyber/event:perf_event", + "//cyber/proto:perf_conf_cc_proto", + "//cyber/time:time", ] ) diff --git a/cybertron/event/perf_event.cc b/cyber/event/perf_event.cc similarity index 89% rename from cybertron/event/perf_event.cc rename to cyber/event/perf_event.cc index 953640bc51c..b26625c8ea1 100644 --- a/cybertron/event/perf_event.cc +++ b/cyber/event/perf_event.cc @@ -20,14 +20,14 @@ #include #include -#include "cybertron/event/perf_event.h" +#include "cyber/event/perf_event.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace event { -using apollo::cybertron::base::BoundedQueue; -using apollo::cybertron::common::GlobalData; +using apollo::cyber::base::BoundedQueue; +using apollo::cyber::common::GlobalData; void SchedPerfEvent::SetParams(const int count, ...) { va_list ap; @@ -54,5 +54,5 @@ void TransportPerfEvent::SetParams(const int count, ...) { } } // namespace event -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/event/perf_event.h b/cyber/event/perf_event.h similarity index 84% rename from cybertron/event/perf_event.h rename to cyber/event/perf_event.h index f428e1a5117..c4de9c50fae 100644 --- a/cybertron/event/perf_event.h +++ b/cyber/event/perf_event.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_EVENT_PERF_EVENT_H_ -#define CYBERTRON_EVENT_PERF_EVENT_H_ +#ifndef CYBER_EVENT_PERF_EVENT_H_ +#define CYBER_EVENT_PERF_EVENT_H_ #include #include @@ -25,19 +25,19 @@ #include #include -#include "cybertron/base/bounded_queue.h" -#include "cybertron/common/global_data.h" -#include "cybertron/common/log.h" -#include "cybertron/common/macros.h" +#include "cyber/base/bounded_queue.h" +#include "cyber/common/global_data.h" +#include "cyber/common/log.h" +#include "cyber/common/macros.h" #define MAX_EVENT_SIZE 16384 namespace apollo { -namespace cybertron { +namespace cyber { namespace event { -using apollo::cybertron::base::BoundedQueue; -using apollo::cybertron::common::GlobalData; +using apollo::cyber::base::BoundedQueue; +using apollo::cyber::common::GlobalData; enum class EventType { SCHED_EVENT = 0, TRANS_EVENT = 1 }; @@ -91,7 +91,7 @@ class SchedPerfEvent : public PerfEventBase { std::stringstream ss; ss << event_type << "\t"; ss << event_id << "\t"; - ss << apollo::cybertron::common::GlobalData::GetTaskNameById(cr_id) << "\t"; + ss << apollo::cyber::common::GlobalData::GetTaskNameById(cr_id) << "\t"; ss << proc_id << "\t"; ss << t_sleep << "\t"; ss << t_start << "\t"; @@ -122,7 +122,7 @@ class TransportPerfEvent : public PerfEventBase { std::stringstream ss; ss << event_type << "\t"; ss << event_id << "\t"; - ss << apollo::cybertron::common::GlobalData::GetChannelById(channel_id) + ss << apollo::cyber::common::GlobalData::GetChannelById(channel_id) << "\t"; ss << msg_seq << "\t"; ss << t_end; @@ -135,7 +135,7 @@ class TransportPerfEvent : public PerfEventBase { }; } // namespace event -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_EVENT_PERF_EVENT_H_ +#endif // CYBER_EVENT_PERF_EVENT_H_ diff --git a/cybertron/event/perf_event_cache.cc b/cyber/event/perf_event_cache.cc similarity index 89% rename from cybertron/event/perf_event_cache.cc rename to cyber/event/perf_event_cache.cc index 335b000d7c4..3138a960df1 100644 --- a/cybertron/event/perf_event_cache.cc +++ b/cyber/event/perf_event_cache.cc @@ -19,13 +19,13 @@ #include #include -#include "cybertron/common/global_data.h" -#include "cybertron/event/perf_event_cache.h" -#include "cybertron/init.h" -#include "cybertron/time/time.h" +#include "cyber/common/global_data.h" +#include "cyber/event/perf_event_cache.h" +#include "cyber/init.h" +#include "cyber/time/time.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace event { PerfEventCache::PerfEventCache() { @@ -53,7 +53,7 @@ PerfEventCache::~PerfEventCache() { io_thread_.join(); } - of_ << cybertron::Time::Now().ToNanosecond() << std::endl; + of_ << cyber::Time::Now().ToNanosecond() << std::endl; of_.flush(); of_.close(); } @@ -76,7 +76,7 @@ void PerfEventCache::AddSchedEvent(const SchedPerf event_id, if (!enable_) { return; } - if (perf_conf_.type() != apollo::cybertron::proto::SCHED) { + if (perf_conf_.type() != apollo::cyber::proto::SCHED) { return; } @@ -95,7 +95,7 @@ void PerfEventCache::AddTransportEvent(const TransPerf event_id, if (!enable_) { return; } - if (perf_conf_.type() != apollo::cybertron::proto::SCHED) { + if (perf_conf_.type() != apollo::cyber::proto::SCHED) { return; } @@ -110,7 +110,7 @@ void PerfEventCache::AddTransportEvent(const TransPerf event_id, void PerfEventCache::Run() { std::shared_ptr event; int buf_size = 0; - while (!shutdown_ && !apollo::cybertron::IsShutdown()) { + while (!shutdown_ && !apollo::cyber::IsShutdown()) { if (event_queue_.WaitDequeue(&event)) { of_ << event->SerializeToString() << std::endl; buf_size++; @@ -131,5 +131,5 @@ void PerfEventCache::Start() { } } // namespace event -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/event/perf_event_cache.h b/cyber/event/perf_event_cache.h similarity index 77% rename from cybertron/event/perf_event_cache.h rename to cyber/event/perf_event_cache.h index 9d77e8a76bf..d59de3bc911 100644 --- a/cybertron/event/perf_event_cache.h +++ b/cyber/event/perf_event_cache.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_PERF_EVENT_CACHE_H_ -#define CYBERTRON_PERF_EVENT_CACHE_H_ +#ifndef CYBER_PERF_EVENT_CACHE_H_ +#define CYBER_PERF_EVENT_CACHE_H_ #include #include @@ -24,22 +24,22 @@ #include #include -#include "cybertron/base/bounded_queue.h" -#include "cybertron/common/global_data.h" -#include "cybertron/common/log.h" -#include "cybertron/common/macros.h" -#include "cybertron/event/perf_event.h" -#include "cybertron/proto/perf_conf.pb.h" +#include "cyber/base/bounded_queue.h" +#include "cyber/common/global_data.h" +#include "cyber/common/log.h" +#include "cyber/common/macros.h" +#include "cyber/event/perf_event.h" +#include "cyber/proto/perf_conf.pb.h" #define MAX_EVENT_SIZE 16384 namespace apollo { -namespace cybertron { +namespace cyber { namespace event { -using apollo::cybertron::base::BoundedQueue; -using apollo::cybertron::common::GlobalData; -using apollo::cybertron::proto::PerfConf; +using apollo::cyber::base::BoundedQueue; +using apollo::cyber::common::GlobalData; +using apollo::cyber::proto::PerfConf; class PerfEventCache { public: @@ -65,7 +65,7 @@ class PerfEventCache { DECLARE_SINGLETON(PerfEventCache) }; } // namespace event -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_INIT_H_ +#endif // CYBER_INIT_H_ diff --git a/cybertron/init.cc b/cyber/init.cc similarity index 75% rename from cybertron/init.cc rename to cyber/init.cc index b9c4808b8bd..547b93d4f96 100644 --- a/cybertron/init.cc +++ b/cyber/init.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/init.h" +#include "cyber/init.h" #include #include @@ -24,36 +24,36 @@ #include #include -#include "cybertron/binary.h" -#include "cybertron/common/environment.h" -#include "cybertron/common/file.h" -#include "cybertron/common/global_data.h" -#include "cybertron/data/data_dispatcher.h" -#include "cybertron/event/perf_event_cache.h" -#include "cybertron/logger/async_logger.h" -#include "cybertron/node/node.h" -#include "cybertron/scheduler/scheduler.h" -#include "cybertron/service_discovery/topology_manager.h" -#include "cybertron/task/task.h" -#include "cybertron/transport/transport.h" +#include "cyber/binary.h" +#include "cyber/common/environment.h" +#include "cyber/common/file.h" +#include "cyber/common/global_data.h" +#include "cyber/data/data_dispatcher.h" +#include "cyber/event/perf_event_cache.h" +#include "cyber/logger/async_logger.h" +#include "cyber/node/node.h" +#include "cyber/scheduler/scheduler.h" +#include "cyber/service_discovery/topology_manager.h" +#include "cyber/task/task.h" +#include "cyber/transport/transport.h" namespace apollo { -namespace cybertron { +namespace cyber { -using apollo::cybertron::common::EnsureDirectory; -using apollo::cybertron::common::GetAbsolutePath; -using apollo::cybertron::common::GetProtoFromFile; -using apollo::cybertron::common::WorkRoot; -using apollo::cybertron::croutine::CRoutine; -using apollo::cybertron::event::PerfEventCache; -using apollo::cybertron::scheduler::Scheduler; -using apollo::cybertron::service_discovery::TopologyManager; +using apollo::cyber::common::EnsureDirectory; +using apollo::cyber::common::GetAbsolutePath; +using apollo::cyber::common::GetProtoFromFile; +using apollo::cyber::common::WorkRoot; +using apollo::cyber::croutine::CRoutine; +using apollo::cyber::event::PerfEventCache; +using apollo::cyber::scheduler::Scheduler; +using apollo::cyber::service_discovery::TopologyManager; static bool g_atexit_registered = false; // TODO(hewei03): why not use simple mutex? static std::recursive_mutex g_mutex; -static ::apollo::cybertron::logger::AsyncLogger* async_logger; +static ::apollo::cyber::logger::AsyncLogger* async_logger; void OnShutdown(int sig) { (void)sig; @@ -99,9 +99,9 @@ bool Init() { bool Init(const char* argv) { const char* slash = strrchr(argv, '/'); if (slash) { - ::apollo::cybertron::Binary::SetName(slash + 1); + ::apollo::cyber::Binary::SetName(slash + 1); } else { - ::apollo::cybertron::Binary::SetName(argv); + ::apollo::cyber::Binary::SetName(argv); } // Get log conf object @@ -130,7 +130,7 @@ bool Init(const char* argv) { google::SetLogDestination(google::WARNING, ""); google::SetLogDestination(google::FATAL, ""); - async_logger = new ::apollo::cybertron::logger::AsyncLogger( + async_logger = new ::apollo::cyber::logger::AsyncLogger( google::base::GetLogger(FLAGS_minloglevel), 2 * 1024 * 1024); google::base::SetLogger(FLAGS_minloglevel, async_logger); async_logger->Start(); @@ -156,5 +156,5 @@ void Shutdown() { SetState(STATE_SHUTDOWN); } -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/init.h b/cyber/init.h similarity index 85% rename from cybertron/init.h rename to cyber/init.h index 96125b2f8b7..aa693b409a8 100644 --- a/cybertron/init.h +++ b/cyber/init.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_INIT_H_ -#define CYBERTRON_INIT_H_ +#ifndef CYBER_INIT_H_ +#define CYBER_INIT_H_ #include #include @@ -23,11 +23,11 @@ #include #include -#include "cybertron/common/log.h" -#include "cybertron/state.h" +#include "cyber/common/log.h" +#include "cyber/state.h" namespace apollo { -namespace cybertron { +namespace cyber { bool Init(); bool Init(const char* argv); @@ -39,7 +39,7 @@ inline void AsyncShutdown() { } } -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_INIT_H_ +#endif // CYBER_INIT_H_ diff --git a/cybertron/logger/BUILD b/cyber/logger/BUILD similarity index 73% rename from cybertron/logger/BUILD rename to cyber/logger/BUILD index 5c1dc691a66..acd7b0c2b11 100644 --- a/cybertron/logger/BUILD +++ b/cyber/logger/BUILD @@ -11,8 +11,8 @@ cc_library( "logger.h", ]), deps = [ - "//cybertron/common:common", - "//cybertron/logger:log_file_object", + "//cyber/common:common", + "//cyber/logger:log_file_object", ], ) @@ -23,7 +23,7 @@ cc_test( "logger_test.cc", ], deps = [ - "//cybertron", + "//cyber", "@gtest//:main", ], ) @@ -37,8 +37,8 @@ cc_library( "async_logger.h", ]), deps = [ - "//cybertron/common:macros", - "//cybertron/logger:log_file_object", + "//cyber/common:macros", + "//cyber/logger:log_file_object", ] ) @@ -51,9 +51,9 @@ cc_library( "log_file_object.h", ]), deps = [ - "//cybertron:binary", - "//cybertron/common:log", - "//cybertron/logger:logger_util", + "//cyber:binary", + "//cyber/common:log", + "//cyber/logger:logger_util", ] ) diff --git a/cybertron/logger/async_logger.cc b/cyber/logger/async_logger.cc similarity index 97% rename from cybertron/logger/async_logger.cc rename to cyber/logger/async_logger.cc index 7ae19573ed5..11161afc647 100644 --- a/cybertron/logger/async_logger.cc +++ b/cyber/logger/async_logger.cc @@ -14,17 +14,17 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/logger/async_logger.h" +#include "cyber/logger/async_logger.h" #include #include #include #include -#include "cybertron/logger/log_file_object.h" +#include "cyber/logger/log_file_object.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace logger { static std::unordered_map moduleLoggerMap; @@ -196,5 +196,5 @@ bool AsyncLogger::BufferFull(const Buffer& buf) const { } } // namespace logger -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/logger/async_logger.h b/cyber/logger/async_logger.h similarity index 96% rename from cybertron/logger/async_logger.h rename to cyber/logger/async_logger.h index b0880f227cd..c9f08db014b 100644 --- a/cybertron/logger/async_logger.h +++ b/cyber/logger/async_logger.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef INCLUDE_CYBERTRON_COMMON_ASYNC_LOGGER_H_ -#define INCLUDE_CYBERTRON_COMMON_ASYNC_LOGGER_H_ +#ifndef INCLUDE_CYBER_COMMON_ASYNC_LOGGER_H_ +#define INCLUDE_CYBER_COMMON_ASYNC_LOGGER_H_ #include #include @@ -28,11 +28,11 @@ #include #include -#include "cybertron/common/macros.h" +#include "cyber/common/macros.h" #include "glog/logging.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace logger { // Wrapper for a glog Logger which asynchronously writes log messages. @@ -198,7 +198,7 @@ class AsyncLogger : public google::base::Logger { }; } // namespace logger -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_COMMON_ASYNC_LOGGER_H_ +#endif // CYBER_COMMON_ASYNC_LOGGER_H_ diff --git a/cybertron/logger/log_file_object.cc b/cyber/logger/log_file_object.cc similarity index 93% rename from cybertron/logger/log_file_object.cc rename to cyber/logger/log_file_object.cc index 1c2a362691f..40ae57669f8 100644 --- a/cybertron/logger/log_file_object.cc +++ b/cyber/logger/log_file_object.cc @@ -46,7 +46,7 @@ * See the License for the specific language governing permissions and * limitations under the License. *****************************************************************************/ -#include "cybertron/logger/log_file_object.h" +#include "cyber/logger/log_file_object.h" #include #include @@ -56,11 +56,11 @@ #include #include -#include "cybertron/common/log.h" -#include "cybertron/logger/logger_util.h" +#include "cyber/common/log.h" +#include "cyber/logger/logger_util.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace logger { #define PATH_SEPARATOR '/' @@ -138,7 +138,7 @@ void LogFileObject::FlushUnlocked() { } // Figure out when we are due for another flush. const int64_t next = static_cast(2000000); // in usec - next_flush_time_ = apollo::cybertron::logger::CycleClock_Now() + next; + next_flush_time_ = apollo::cyber::logger::CycleClock_Now() + next; } bool LogFileObject::CreateLogfile(const std::string& time_pid_string) { @@ -197,8 +197,8 @@ void LogFileObject::Write(bool force_flush, time_t timestamp, } if (static_cast(file_length_ >> 20) >= - ::apollo::cybertron::logger::MaxLogSize() || - apollo::cybertron::logger::PidHasChanged()) { + ::apollo::cyber::logger::MaxLogSize() || + apollo::cyber::logger::PidHasChanged()) { if (file_ != nullptr) fclose(file_); file_ = nullptr; file_length_ = bytes_since_flush_ = dropped_mem_length_ = 0; @@ -225,11 +225,11 @@ void LogFileObject::Write(bool force_flush, time_t timestamp, << 1 + tm_time.tm_mon << std::setw(2) << tm_time.tm_mday << '-' << std::setw(2) << tm_time.tm_hour << std::setw(2) << tm_time.tm_min << std::setw(2) << tm_time.tm_sec << '.' - << apollo::cybertron::logger::GetMainThreadPid(); + << apollo::cyber::logger::GetMainThreadPid(); const std::string& time_pid_string = time_pid_stream.str(); std::string host_name; - apollo::cybertron::logger::GetHostName(&host_name); + apollo::cyber::logger::GetHostName(&host_name); if (base_filename_selected_) { bool success = false; @@ -237,7 +237,7 @@ void LogFileObject::Write(bool force_flush, time_t timestamp, base_filename_ + ".log." + LC_LOG_SEVERITY_NAMES[severity_] + "."; const std::vector& log_dirs = - ::apollo::cybertron::logger::GetLoggingDirectories(); + ::apollo::cyber::logger::GetLoggingDirectories(); for (std::vector::const_iterator dir = log_dirs.begin(); dir != log_dirs.end(); ++dir) { @@ -296,7 +296,7 @@ void LogFileObject::Write(bool force_flush, time_t timestamp, bytes_since_flush_ += message_len; } } else { - if (::apollo::cybertron::logger::CycleClock_Now() >= next_flush_time_) { + if (::apollo::cyber::logger::CycleClock_Now() >= next_flush_time_) { stop_writing = false; // check to see if disk has free space. } return; // no need to flush @@ -305,11 +305,11 @@ void LogFileObject::Write(bool force_flush, time_t timestamp, // See important msgs *now*. Also, flush logs at least every 10^6 chars, // or every "FLAGS_logbufsecs" seconds. if (force_flush || (bytes_since_flush_ >= 1000000) || - (::apollo::cybertron::logger::CycleClock_Now() >= next_flush_time_)) { + (::apollo::cyber::logger::CycleClock_Now() >= next_flush_time_)) { FlushUnlocked(); } } } // namespace logger -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/logger/log_file_object.h b/cyber/logger/log_file_object.h similarity index 92% rename from cybertron/logger/log_file_object.h rename to cyber/logger/log_file_object.h index 40a54e0e0e7..659e82104f1 100644 --- a/cybertron/logger/log_file_object.h +++ b/cyber/logger/log_file_object.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_LOGGER_LOG_FILE_OBJECT_H_ -#define CYBERTRON_LOGGER_LOG_FILE_OBJECT_H_ +#ifndef CYBER_LOGGER_LOG_FILE_OBJECT_H_ +#define CYBER_LOGGER_LOG_FILE_OBJECT_H_ #include #include @@ -24,7 +24,7 @@ #include "glog/logging.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace logger { class LogFileObject : public google::base::Logger { @@ -68,7 +68,7 @@ class LogFileObject : public google::base::Logger { }; } // namespace logger -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_LOGGER_LOG_FILE_OBJECT_H_ +#endif // CYBER_LOGGER_LOG_FILE_OBJECT_H_ diff --git a/cybertron/logger/logger.cc b/cyber/logger/logger.cc similarity index 94% rename from cybertron/logger/logger.cc rename to cyber/logger/logger.cc index 7667ca142a9..49ccf35268a 100644 --- a/cybertron/logger/logger.cc +++ b/cyber/logger/logger.cc @@ -20,11 +20,11 @@ #include #include -#include "cybertron/logger/log_file_object.h" -#include "cybertron/logger/logger.h" +#include "cyber/logger/log_file_object.h" +#include "cyber/logger/logger.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace logger { static std::unordered_map moduleLoggerMap; @@ -73,5 +73,5 @@ void Logger::Flush() { wrapped_->Flush(); } uint32_t Logger::LogSize() { return wrapped_->LogSize(); } } // namespace logger -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/logger/logger.h b/cyber/logger/logger.h similarity index 89% rename from cybertron/logger/logger.h rename to cyber/logger/logger.h index 05e1eb14125..174408f49e0 100644 --- a/cybertron/logger/logger.h +++ b/cyber/logger/logger.h @@ -14,14 +14,14 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_LOGGER_LOGGER_H_ -#define CYBERTRON_LOGGER_LOGGER_H_ +#ifndef CYBER_LOGGER_LOGGER_H_ +#define CYBER_LOGGER_LOGGER_H_ #include #include namespace apollo { -namespace cybertron { +namespace cyber { namespace logger { class Logger : public google::base::Logger { @@ -39,7 +39,7 @@ class Logger : public google::base::Logger { }; } // namespace logger -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_LOGGER_LOGGER_H_ +#endif // CYBER_LOGGER_LOGGER_H_ diff --git a/cybertron/logger/logger_test.cc b/cyber/logger/logger_test.cc similarity index 83% rename from cybertron/logger/logger_test.cc rename to cyber/logger/logger_test.cc index 2b9d4bbfd66..88c092b4c83 100644 --- a/cybertron/logger/logger_test.cc +++ b/cyber/logger/logger_test.cc @@ -18,25 +18,25 @@ #include #include -#include "cybertron/logger/logger.h" -#include "cybertron/time/time.h" +#include "cyber/logger/logger.h" +#include "cyber/time/time.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace logger { TEST(LoggerTest, init_and_write) { Logger logger(google::base::GetLogger(google::INFO)); time_t timep; time(&timep); - std::string message = "cybertron logger test"; + std::string message = "cyber logger test"; logger.Write(false, timep, message.c_str(), 20); - message = "**[CybertronLoggerTest]** cybertron logger test"; + message = "**[CyberLoggerTest]** cyber logger test"; logger.Write(false, timep, message.c_str(), 20); logger.LogSize(); logger.Flush(); } } // namespace logger -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/logger/logger_util.h b/cyber/logger/logger_util.h similarity index 92% rename from cybertron/logger/logger_util.h rename to cyber/logger/logger_util.h index fc451d83743..08858c869cf 100644 --- a/cybertron/logger/logger_util.h +++ b/cyber/logger/logger_util.h @@ -18,8 +18,8 @@ * @file */ -#ifndef CYBERTRON_LOGGER_LOGGER_UTIL_H_ -#define CYBERTRON_LOGGER_LOGGER_UTIL_H_ +#ifndef CYBER_LOGGER_LOGGER_UTIL_H_ +#define CYBER_LOGGER_LOGGER_UTIL_H_ #include #include @@ -34,7 +34,7 @@ #include "glog/logging.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace logger { int64_t CycleClock_Now() { @@ -83,7 +83,7 @@ static int32_t MaxLogSize() { } } // namespace logger -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_LOGGER_LOGGER_UTIL_H_ +#endif // CYBER_LOGGER_LOGGER_UTIL_H_ diff --git a/cybertron/mainboard/mainboard.cc b/cyber/mainboard/mainboard.cc similarity index 75% rename from cybertron/mainboard/mainboard.cc rename to cyber/mainboard/mainboard.cc index 450dd73b0c6..851de10d54c 100644 --- a/cybertron/mainboard/mainboard.cc +++ b/cyber/mainboard/mainboard.cc @@ -14,22 +14,22 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/common/log.h" -#include "cybertron/init.h" -#include "cybertron/mainboard/module_argument.h" -#include "cybertron/mainboard/module_controller.h" -#include "cybertron/state.h" +#include "cyber/common/log.h" +#include "cyber/init.h" +#include "cyber/mainboard/module_argument.h" +#include "cyber/mainboard/module_controller.h" +#include "cyber/state.h" #include "gflags/gflags.h" -using apollo::cybertron::mainboard::ModuleArgument; -using apollo::cybertron::mainboard::ModuleController; +using apollo::cyber::mainboard::ModuleArgument; +using apollo::cyber::mainboard::ModuleController; int main(int argc, char** argv) { google::SetUsageMessage("we use this program to load dag and run user apps."); - // initialize cybertron - apollo::cybertron::Init(argv[0]); + // initialize cyber + apollo::cyber::Init(argv[0]); // parse the argument ModuleArgument module_args; @@ -46,9 +46,9 @@ int main(int argc, char** argv) { return -1; } - apollo::cybertron::WaitForShutdown(); + apollo::cyber::WaitForShutdown(); controller.Clear(); - apollo::cybertron::Shutdown(); + apollo::cyber::Shutdown(); AINFO << "exit mainboard."; return 0; diff --git a/cybertron/mainboard/module_argument.cc b/cyber/mainboard/module_argument.cc similarity index 95% rename from cybertron/mainboard/module_argument.cc rename to cyber/mainboard/module_argument.cc index 538513cc05e..aa4ad083dad 100644 --- a/cybertron/mainboard/module_argument.cc +++ b/cyber/mainboard/module_argument.cc @@ -14,14 +14,14 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/mainboard/module_argument.h" +#include "cyber/mainboard/module_argument.h" #include -using apollo::cybertron::common::GlobalData; +using apollo::cyber::common::GlobalData; namespace apollo { -namespace cybertron { +namespace cyber { namespace mainboard { ModuleArgument::ModuleArgument() {} @@ -108,5 +108,5 @@ void ModuleArgument::GetOptions(const int argc, char* const argv[]) { } } // namespace mainboard -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/mainboard/module_argument.h b/cyber/mainboard/module_argument.h similarity index 83% rename from cybertron/mainboard/module_argument.h rename to cyber/mainboard/module_argument.h index 3c8a3ab59b7..b6f626726d8 100644 --- a/cybertron/mainboard/module_argument.h +++ b/cyber/mainboard/module_argument.h @@ -14,18 +14,18 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_MAINBOARD_MODULE_ARGUMENT_H_ -#define CYBERTRON_MAINBOARD_MODULE_ARGUMENT_H_ +#ifndef CYBER_MAINBOARD_MODULE_ARGUMENT_H_ +#define CYBER_MAINBOARD_MODULE_ARGUMENT_H_ #include #include -#include "cybertron/common/global_data.h" -#include "cybertron/common/log.h" -#include "cybertron/common/types.h" +#include "cyber/common/global_data.h" +#include "cyber/common/log.h" +#include "cyber/common/types.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace mainboard { static const char DEFAULT_process_name_[] = "mainboard_default"; @@ -50,7 +50,7 @@ class ModuleArgument { }; } // namespace mainboard -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_MAINBOARD_MODULE_ARGUMENT_H_ +#endif // CYBER_MAINBOARD_MODULE_ARGUMENT_H_ diff --git a/cybertron/mainboard/module_controller.cc b/cyber/mainboard/module_controller.cc similarity index 95% rename from cybertron/mainboard/module_controller.cc rename to cyber/mainboard/module_controller.cc index 0a3f1c399a4..92dbcbfac73 100644 --- a/cybertron/mainboard/module_controller.cc +++ b/cyber/mainboard/module_controller.cc @@ -14,16 +14,16 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/mainboard/module_controller.h" +#include "cyber/mainboard/module_controller.h" #include -#include "cybertron/common/environment.h" -#include "cybertron/common/file.h" -#include "cybertron/component/component_base.h" +#include "cyber/common/environment.h" +#include "cyber/common/file.h" +#include "cyber/component/component_base.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace mainboard { ModuleController::ModuleController(const ModuleArgument& args) { args_ = args; } @@ -143,5 +143,5 @@ bool ModuleController::LoadModule(const std::string& path) { } } // namespace mainboard -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/mainboard/module_controller.h b/cyber/mainboard/module_controller.h similarity index 76% rename from cybertron/mainboard/module_controller.h rename to cyber/mainboard/module_controller.h index e2d78ed871e..bb939eaa5cf 100644 --- a/cybertron/mainboard/module_controller.h +++ b/cyber/mainboard/module_controller.h @@ -14,23 +14,23 @@ * See the License for the specific language governing permissions and * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_MAINBOARD_MODULE_CONTROLLER_H_ -#define CYBERTRON_MAINBOARD_MODULE_CONTROLLER_H_ +#ifndef CYBER_MAINBOARD_MODULE_CONTROLLER_H_ +#define CYBER_MAINBOARD_MODULE_CONTROLLER_H_ #include #include #include -#include "cybertron/class_loader/class_loader_manager.h" -#include "cybertron/component/component.h" -#include "cybertron/mainboard/module_argument.h" -#include "cybertron/proto/dag_config.pb.h" +#include "cyber/class_loader/class_loader_manager.h" +#include "cyber/component/component.h" +#include "cyber/mainboard/module_argument.h" +#include "cyber/proto/dag_config.pb.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace mainboard { -using apollo::cybertron::proto::DagConfig; +using apollo::cyber::proto::DagConfig; class ModuleController { public: @@ -54,7 +54,7 @@ class ModuleController { }; } // namespace mainboard -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_MAINBOARD_MODULE_CONTROLLER_H_ +#endif // CYBER_MAINBOARD_MODULE_CONTROLLER_H_ diff --git a/cybertron/message/BUILD b/cyber/message/BUILD similarity index 87% rename from cybertron/message/BUILD rename to cyber/message/BUILD index e9152c23ed5..4815f4228fe 100644 --- a/cybertron/message/BUILD +++ b/cyber/message/BUILD @@ -42,8 +42,8 @@ cc_test( "message_traits_test.cc", ], deps = [ - "//cybertron", - "//cybertron/proto:unit_test_cc_proto", + "//cyber", + "//cyber/proto:unit_test_cc_proto", "@gtest//:main", ], ) @@ -57,10 +57,10 @@ cc_library( "protobuf_factory.h", ], deps = [ - "//cybertron:init", - "//cybertron/common:macros", - "//cybertron/common:log", - "//cybertron/proto:proto_desc_cc_proto", + "//cyber:init", + "//cyber/common:macros", + "//cyber/common:log", + "//cyber/proto:proto_desc_cc_proto", ] ) @@ -106,7 +106,7 @@ cc_test( "raw_message_test.cc", ], deps = [ - "//cybertron", + "//cyber", "@gtest//:main", ], ) diff --git a/cybertron/message/intra_message.cc b/cyber/message/intra_message.cc similarity index 90% rename from cybertron/message/intra_message.cc rename to cyber/message/intra_message.cc index aea33a84fe5..cf69134e5c0 100644 --- a/cybertron/message/intra_message.cc +++ b/cyber/message/intra_message.cc @@ -14,14 +14,14 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/message/intra_message.h" +#include "cyber/message/intra_message.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace message { const char* IntraMessage::type_name_ = "IntraMessage"; } // namespace message -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/message/intra_message.h b/cyber/message/intra_message.h similarity index 87% rename from cybertron/message/intra_message.h rename to cyber/message/intra_message.h index 045acce8110..0d53658a844 100644 --- a/cybertron/message/intra_message.h +++ b/cyber/message/intra_message.h @@ -14,15 +14,15 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_MESSAGE_INTRA_MESSAGE_H_ -#define CYBERTRON_MESSAGE_INTRA_MESSAGE_H_ +#ifndef CYBER_MESSAGE_INTRA_MESSAGE_H_ +#define CYBER_MESSAGE_INTRA_MESSAGE_H_ #include #include #include namespace apollo { -namespace cybertron { +namespace cyber { namespace message { class IntraMessage { @@ -40,7 +40,7 @@ class IntraMessage { }; } // namespace message -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_MESSAGE_INTRA_MESSAGE_H_ +#endif // CYBER_MESSAGE_INTRA_MESSAGE_H_ diff --git a/cybertron/message/intra_message_traits.h b/cyber/message/intra_message_traits.h similarity index 89% rename from cybertron/message/intra_message_traits.h rename to cyber/message/intra_message_traits.h index 9c23a945a0e..cf9b598aa98 100644 --- a/cybertron/message/intra_message_traits.h +++ b/cyber/message/intra_message_traits.h @@ -14,17 +14,17 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_MESSAGE_INTRA_MESSAGE_TRAITS_H_ -#define CYBERTRON_MESSAGE_INTRA_MESSAGE_TRAITS_H_ +#ifndef CYBER_MESSAGE_INTRA_MESSAGE_TRAITS_H_ +#define CYBER_MESSAGE_INTRA_MESSAGE_TRAITS_H_ #include #include #include -#include "cybertron/message/intra_message.h" +#include "cyber/message/intra_message.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace message { template #include -#include "cybertron/message/message_traits.h" -#include "cybertron/proto/unit_test.pb.h" +#include "cyber/message/message_traits.h" +#include "cyber/proto/unit_test.pb.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace message { TEST(MessageTraitsTest, serialize_to_string) { @@ -44,13 +44,13 @@ TEST(MessageTraitsTest, parse_from_string) { TEST(MessageTraitsTest, message_type) { std::string msg_type = MessageType(); - EXPECT_EQ(msg_type, "apollo.cybertron.proto.UnitTest"); + EXPECT_EQ(msg_type, "apollo.cyber.proto.UnitTest"); proto::UnitTest ut; msg_type = MessageType(ut); - EXPECT_EQ(msg_type, "apollo.cybertron.proto.UnitTest"); + EXPECT_EQ(msg_type, "apollo.cyber.proto.UnitTest"); } } // namespace message -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/message/protobuf_factory.cc b/cyber/message/protobuf_factory.cc similarity index 98% rename from cybertron/message/protobuf_factory.cc rename to cyber/message/protobuf_factory.cc index e84ebbcf202..2a5b0f8df14 100644 --- a/cybertron/message/protobuf_factory.cc +++ b/cyber/message/protobuf_factory.cc @@ -14,11 +14,11 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/message/protobuf_factory.h" -#include "cybertron/common/log.h" +#include "cyber/message/protobuf_factory.h" +#include "cyber/common/log.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace message { using google::protobuf::MessageFactory; @@ -223,5 +223,5 @@ void ErrorCollector::AddWarning(const std::string& filename, } } // namespace message -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/message/protobuf_factory.h b/cyber/message/protobuf_factory.h similarity index 93% rename from cybertron/message/protobuf_factory.h rename to cyber/message/protobuf_factory.h index 7f9435ed55c..a5674fbc761 100644 --- a/cybertron/message/protobuf_factory.h +++ b/cyber/message/protobuf_factory.h @@ -14,26 +14,26 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_MESSAGE_PROTOBUF_FACTORY_H_ -#define CYBERTRON_MESSAGE_PROTOBUF_FACTORY_H_ +#ifndef CYBER_MESSAGE_PROTOBUF_FACTORY_H_ +#define CYBER_MESSAGE_PROTOBUF_FACTORY_H_ #include #include #include #include -#include "cybertron/common/macros.h" -#include "cybertron/proto/proto_desc.pb.h" +#include "cyber/common/macros.h" +#include "cyber/proto/proto_desc.pb.h" #include "google/protobuf/compiler/parser.h" #include "google/protobuf/descriptor.h" #include "google/protobuf/dynamic_message.h" #include "google/protobuf/io/tokenizer.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace message { -using apollo::cybertron::proto::ProtoDesc; +using apollo::cyber::proto::ProtoDesc; using google::protobuf::DescriptorPool; using google::protobuf::DynamicMessageFactory; using google::protobuf::FileDescriptor; @@ -109,7 +109,7 @@ class ProtobufFactory { }; } // namespace message -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_MESSAGE_PROTOBUF_FACTORY_H_ +#endif // CYBER_MESSAGE_PROTOBUF_FACTORY_H_ diff --git a/cybertron/message/protobuf_traits.h b/cyber/message/protobuf_traits.h similarity index 92% rename from cybertron/message/protobuf_traits.h rename to cyber/message/protobuf_traits.h index 1c5f0015cb4..488c6ec4af8 100644 --- a/cybertron/message/protobuf_traits.h +++ b/cyber/message/protobuf_traits.h @@ -14,17 +14,17 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_MESSAGE_PROTOBUF_TRAITS_H_ -#define CYBERTRON_MESSAGE_PROTOBUF_TRAITS_H_ +#ifndef CYBER_MESSAGE_PROTOBUF_TRAITS_H_ +#define CYBER_MESSAGE_PROTOBUF_TRAITS_H_ #include #include #include -#include "cybertron/message/protobuf_factory.h" +#include "cyber/message/protobuf_factory.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace message { template #include #include -#include "cybertron/common/macros.h" +#include "cyber/common/macros.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace message { static const char* const PY_MESSAGE_FULLNAME = - "apollo.cybertron.message.PyMessage"; + "apollo.cyber.message.PyMessage"; // static const std::string data_split_pattern = "#@"; class PyMessageWrap { @@ -103,7 +103,7 @@ inline const PyMessageWrap::Descriptor* PyMessageWrap::descriptor() { inline std::string PyMessageWrap::TypeName() { return PY_MESSAGE_FULLNAME; } } // namespace message -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_MESSAGE_PY_MESSAGE_H_ +#endif // CYBER_MESSAGE_PY_MESSAGE_H_ diff --git a/cybertron/message/py_message_traits.h b/cyber/message/py_message_traits.h similarity index 87% rename from cybertron/message/py_message_traits.h rename to cyber/message/py_message_traits.h index 210ffb759ae..3dbd9193b49 100644 --- a/cybertron/message/py_message_traits.h +++ b/cyber/message/py_message_traits.h @@ -14,18 +14,18 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_MESSAGE_PY_MESSAGE_TRAITS_H_ -#define CYBERTRON_MESSAGE_PY_MESSAGE_TRAITS_H_ +#ifndef CYBER_MESSAGE_PY_MESSAGE_TRAITS_H_ +#define CYBER_MESSAGE_PY_MESSAGE_TRAITS_H_ #include #include #include -#include "cybertron/message/protobuf_factory.h" -#include "cybertron/message/py_message.h" +#include "cyber/message/protobuf_factory.h" +#include "cyber/message/py_message.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace message { // Template specialization for RawMessage @@ -58,7 +58,7 @@ inline void GetDescriptorString(const std::string& type, } } // namespace message -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_MESSAGE_PY_MESSAGE_TRAITS_H_ +#endif // CYBER_MESSAGE_PY_MESSAGE_TRAITS_H_ diff --git a/cybertron/message/raw_message.h b/cyber/message/raw_message.h similarity index 88% rename from cybertron/message/raw_message.h rename to cyber/message/raw_message.h index b6db5a76a52..9785de3ed34 100644 --- a/cybertron/message/raw_message.h +++ b/cyber/message/raw_message.h @@ -14,15 +14,15 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_MESSAGE_RAW_MESSAGE_H_ -#define CYBERTRON_MESSAGE_RAW_MESSAGE_H_ +#ifndef CYBER_MESSAGE_RAW_MESSAGE_H_ +#define CYBER_MESSAGE_RAW_MESSAGE_H_ #include #include #include namespace apollo { -namespace cybertron { +namespace cyber { namespace message { struct RawMessage { @@ -61,7 +61,7 @@ struct RawMessage { } static std::string TypeName() { - return "apollo.cybertron.message.RawMessage"; + return "apollo.cyber.message.RawMessage"; } std::string message; @@ -69,7 +69,7 @@ struct RawMessage { }; } // namespace message -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_MESSAGE_RAW_MESSAGE_H_ +#endif // CYBER_MESSAGE_RAW_MESSAGE_H_ diff --git a/cybertron/message/raw_message_test.cc b/cyber/message/raw_message_test.cc similarity index 88% rename from cybertron/message/raw_message_test.cc rename to cyber/message/raw_message_test.cc index d1e39a7effa..413387af44a 100644 --- a/cybertron/message/raw_message_test.cc +++ b/cyber/message/raw_message_test.cc @@ -17,10 +17,10 @@ #include #include -#include "cybertron/message/raw_message.h" +#include "cyber/message/raw_message.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace message { TEST(RawMessageTest, constructor) { @@ -48,12 +48,12 @@ TEST(RawMessageTest, parse_from_string) { TEST(RawMessageTest, message_type) { RawMessage msg; std::string msg_type = RawMessage::TypeName(); - EXPECT_EQ(msg_type, "apollo.cybertron.message.RawMessage"); + EXPECT_EQ(msg_type, "apollo.cyber.message.RawMessage"); // msg_type = MessageType(); - // EXPECT_EQ(msg_type, "apollo.cybertron.message.RawMessage"); + // EXPECT_EQ(msg_type, "apollo.cyber.message.RawMessage"); } } // namespace message -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/message/raw_message_traits.h b/cyber/message/raw_message_traits.h similarity index 86% rename from cybertron/message/raw_message_traits.h rename to cyber/message/raw_message_traits.h index 4783f50ae33..dce17a8337b 100644 --- a/cybertron/message/raw_message_traits.h +++ b/cyber/message/raw_message_traits.h @@ -14,18 +14,18 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_MESSAGE_RAW_MESSAGE_TRAITS_H_ -#define CYBERTRON_MESSAGE_RAW_MESSAGE_TRAITS_H_ +#ifndef CYBER_MESSAGE_RAW_MESSAGE_TRAITS_H_ +#define CYBER_MESSAGE_RAW_MESSAGE_TRAITS_H_ #include #include #include -#include "cybertron/message/protobuf_factory.h" -#include "cybertron/message/raw_message.h" +#include "cyber/message/protobuf_factory.h" +#include "cyber/message/raw_message.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace message { // Template specialization for RawMessage @@ -58,7 +58,7 @@ inline void GetDescriptorString(const std::string& type, } } // namespace message -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_MESSAGE_RAW_MESSAGE_TRAITS_H_ +#endif // CYBER_MESSAGE_RAW_MESSAGE_TRAITS_H_ diff --git a/cyber/node/BUILD b/cyber/node/BUILD new file mode 100644 index 00000000000..3b620c96a32 --- /dev/null +++ b/cyber/node/BUILD @@ -0,0 +1,65 @@ +load("//tools:cpplint.bzl", "cpplint") + +package(default_visibility = ["//visibility:public"]) + +cc_library( + name = "reader_base", + hdrs = glob([ + "reader_base.h", + ]), + deps = [ + "//cyber/transport:transport_lib", + "//cyber/common:common", + "//cyber/event:perf_event_cache", + ], +) + +cc_library( + name = "node", + srcs = glob([ + "node.cc", + ]), + hdrs = glob([ + "*.h", + ]), + deps = [ + "//cyber/transport:transport_lib", + "//cyber/blocker:intra_reader", + "//cyber/blocker:intra_writer", + "//cyber/croutine:croutine", + "//cyber/data:data_visitor", + "//cyber/scheduler:scheduler", + "//cyber/service:client", + "//cyber/service:service", + "//cyber/service_discovery:topology_manager", + "//cyber/proto:topology_change_cc_proto", + ], +) + +cc_test( + name = "node_test", + size = "small", + srcs = [ + "node_test.cc", + ], + deps = [ + "//cyber", + "//cyber/proto:unit_test_cc_proto", + "@gtest//:main", + ], +) + +cc_test( + name = "writer_reader_test", + size = "small", + srcs = [ + "writer_reader_test.cc", + ], + deps = [ + "//cyber", + "//cyber/proto:unit_test_cc_proto", + "@gtest//:main", + ], +) + +cpplint() diff --git a/cybertron/node/node.cc b/cyber/node/node.cc similarity index 89% rename from cybertron/node/node.cc rename to cyber/node/node.cc index d29af288c28..750c32bf4ab 100644 --- a/cybertron/node/node.cc +++ b/cyber/node/node.cc @@ -14,12 +14,12 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/node/node.h" -#include "cybertron/common/global_data.h" -#include "cybertron/time/time.h" +#include "cyber/node/node.h" +#include "cyber/common/global_data.h" +#include "cyber/time/time.h" namespace apollo { -namespace cybertron { +namespace cyber { using proto::RoleType; @@ -45,5 +45,5 @@ void Node::ClearData() { } } -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/node/node.h b/cyber/node/node.h similarity index 93% rename from cybertron/node/node.h rename to cyber/node/node.h index 5d0cfc7ba84..b4dc938ff1a 100644 --- a/cybertron/node/node.h +++ b/cyber/node/node.h @@ -14,19 +14,19 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_NODE_NODE_H_ -#define CYBERTRON_NODE_NODE_H_ +#ifndef CYBER_NODE_NODE_H_ +#define CYBER_NODE_NODE_H_ #include #include #include #include -#include "cybertron/node/node_channel_impl.h" -#include "cybertron/node/node_service_impl.h" +#include "cyber/node/node_channel_impl.h" +#include "cyber/node/node_service_impl.h" namespace apollo { -namespace cybertron { +namespace cyber { template class Component; @@ -49,17 +49,17 @@ class Node { template auto CreateReader(const std::string& channel_name, const CallbackFunc& reader_func = nullptr) - -> std::shared_ptr>; + -> std::shared_ptr>; template auto CreateReader(const ReaderConfig& config, const CallbackFunc& reader_func = nullptr) - -> std::shared_ptr>; + -> std::shared_ptr>; template auto CreateReader(const proto::RoleAttributes& role_attr, const CallbackFunc& reader_func = nullptr) - -> std::shared_ptr>; + -> std::shared_ptr>; template auto CreateWriter(const std::string& channel_name) @@ -129,7 +129,7 @@ auto Node::CreateReader(const proto::RoleAttributes& role_attr, template auto Node::CreateReader(const ReaderConfig& config, const CallbackFunc& reader_func) - -> std::shared_ptr> { + -> std::shared_ptr> { std::lock_guard lg(readers_mutex_); if (readers_.find(config.channel_name) != readers_.end()) { AWARN << "Failed to create reader: reader with the same channel already " @@ -189,7 +189,7 @@ auto Node::GetReader(const std::string& name) return nullptr; } -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_NODE_NODE_H_ +#endif // CYBER_NODE_NODE_H_ diff --git a/cybertron/node/node_channel_impl.h b/cyber/node/node_channel_impl.h similarity index 94% rename from cybertron/node/node_channel_impl.h rename to cyber/node/node_channel_impl.h index 6b4694de253..72e2ad78560 100644 --- a/cybertron/node/node_channel_impl.h +++ b/cyber/node/node_channel_impl.h @@ -14,22 +14,22 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_NODE_NODE_CHANNEL_IMPL_H_ -#define CYBERTRON_NODE_NODE_CHANNEL_IMPL_H_ +#ifndef CYBER_NODE_NODE_CHANNEL_IMPL_H_ +#define CYBER_NODE_NODE_CHANNEL_IMPL_H_ #include #include -#include "cybertron/blocker/intra_reader.h" -#include "cybertron/blocker/intra_writer.h" -#include "cybertron/common/global_data.h" -#include "cybertron/message/message_traits.h" -#include "cybertron/node/reader.h" -#include "cybertron/node/writer.h" -#include "cybertron/proto/run_mode_conf.pb.h" +#include "cyber/blocker/intra_reader.h" +#include "cyber/blocker/intra_writer.h" +#include "cyber/common/global_data.h" +#include "cyber/message/message_traits.h" +#include "cyber/node/reader.h" +#include "cyber/node/writer.h" +#include "cyber/proto/run_mode_conf.pb.h" namespace apollo { -namespace cybertron { +namespace cyber { class Node; @@ -230,7 +230,7 @@ void NodeChannelImpl::FillInAttr(proto::RoleAttributes* attr) { } } -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_NODE_NODE_CHANNEL_IMPL_H_ +#endif // CYBER_NODE_NODE_CHANNEL_IMPL_H_ diff --git a/cybertron/node/node_service_impl.h b/cyber/node/node_service_impl.h similarity index 90% rename from cybertron/node/node_service_impl.h rename to cyber/node/node_service_impl.h index 1ecb756e990..05641d035aa 100644 --- a/cybertron/node/node_service_impl.h +++ b/cyber/node/node_service_impl.h @@ -14,20 +14,20 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_NODE_NODE_SERVICE_IMPL_H_ -#define CYBERTRON_NODE_NODE_SERVICE_IMPL_H_ +#ifndef CYBER_NODE_NODE_SERVICE_IMPL_H_ +#define CYBER_NODE_NODE_SERVICE_IMPL_H_ #include #include #include -#include "cybertron/common/global_data.h" -#include "cybertron/service/client.h" -#include "cybertron/service/service.h" -#include "cybertron/service_discovery/topology_manager.h" +#include "cyber/common/global_data.h" +#include "cyber/service/client.h" +#include "cyber/service/service.h" +#include "cyber/service_discovery/topology_manager.h" namespace apollo { -namespace cybertron { +namespace cyber { class Node; @@ -99,7 +99,7 @@ auto NodeServiceImpl::CreateClient(const std::string& service_name) -> return client_ptr; } -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_NODE_NODE_SERVICE_IMPL_H_ +#endif // CYBER_NODE_NODE_SERVICE_IMPL_H_ diff --git a/cybertron/node/node_test.cc b/cyber/node/node_test.cc similarity index 84% rename from cybertron/node/node_test.cc rename to cyber/node/node_test.cc index df0ced407e4..ecba1b7370e 100644 --- a/cybertron/node/node_test.cc +++ b/cyber/node/node_test.cc @@ -16,10 +16,10 @@ #include "gtest/gtest.h" -#include "cybertron/init.h" -#include "cybertron/node/node.h" -#include "cybertron/proto/unit_test.pb.h" +#include "cyber/init.h" +#include "cyber/node/node.h" +#include "cyber/proto/unit_test.pb.h" namespace apollo { -namespace cybertron {} // namespace cybertron +namespace cyber {} // namespace cyber } // namespace apollo diff --git a/cybertron/node/reader.h b/cyber/node/reader.h similarity index 94% rename from cybertron/node/reader.h rename to cyber/node/reader.h index 946c2f12d63..69dd33fde18 100644 --- a/cybertron/node/reader.h +++ b/cyber/node/reader.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_NODE_READER_H_ -#define CYBERTRON_NODE_READER_H_ +#ifndef CYBER_NODE_READER_H_ +#define CYBER_NODE_READER_H_ #include #include @@ -26,18 +26,18 @@ #include #include -#include "cybertron/common/global_data.h" -#include "cybertron/croutine/routine_factory.h" -#include "cybertron/data/data_visitor.h" -#include "cybertron/node/reader_base.h" -#include "cybertron/proto/topology_change.pb.h" -#include "cybertron/scheduler/scheduler.h" -#include "cybertron/service_discovery/topology_manager.h" -#include "cybertron/time/time.h" -#include "cybertron/transport/transport.h" +#include "cyber/common/global_data.h" +#include "cyber/croutine/routine_factory.h" +#include "cyber/data/data_visitor.h" +#include "cyber/node/reader_base.h" +#include "cyber/proto/topology_change.pb.h" +#include "cyber/scheduler/scheduler.h" +#include "cyber/service_discovery/topology_manager.h" +#include "cyber/time/time.h" +#include "cyber/transport/transport.h" namespace apollo { -namespace cybertron { +namespace cyber { template using CallbackFunc = std::function&)>; @@ -293,7 +293,7 @@ uint32_t Reader::GetHistoryDepth() const { return history_depth_; } -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_NODE_READER_H_ +#endif // CYBER_NODE_READER_H_ diff --git a/cybertron/node/reader_base.h b/cyber/node/reader_base.h similarity index 88% rename from cybertron/node/reader_base.h rename to cyber/node/reader_base.h index 721c187b842..0b63577c84f 100644 --- a/cybertron/node/reader_base.h +++ b/cyber/node/reader_base.h @@ -14,25 +14,25 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_NODE_READER_BASE_H_ -#define CYBERTRON_NODE_READER_BASE_H_ +#ifndef CYBER_NODE_READER_BASE_H_ +#define CYBER_NODE_READER_BASE_H_ #include #include #include #include -#include "cybertron/common/macros.h" -#include "cybertron/common/util.h" -#include "cybertron/event/perf_event_cache.h" -#include "cybertron/transport/transport.h" +#include "cyber/common/macros.h" +#include "cyber/common/util.h" +#include "cyber/event/perf_event_cache.h" +#include "cyber/transport/transport.h" namespace apollo { -namespace cybertron { +namespace cyber { -using apollo::cybertron::common::GlobalData; -using apollo::cybertron::event::PerfEventCache; -using apollo::cybertron::event::TransPerf; +using apollo::cyber::common::GlobalData; +using apollo::cyber::event::PerfEventCache; +using apollo::cyber::event::TransPerf; class ReaderBase { public: @@ -115,7 +115,7 @@ auto ReceiverManager::GetReceiver( return receiver_map_[channel_name]; } -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_NODE_READER_BASE_H_ +#endif // CYBER_NODE_READER_BASE_H_ diff --git a/cybertron/node/writer.h b/cyber/node/writer.h similarity index 91% rename from cybertron/node/writer.h rename to cyber/node/writer.h index f33d2b302b0..7f45ee631f6 100644 --- a/cybertron/node/writer.h +++ b/cyber/node/writer.h @@ -14,21 +14,21 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_NODE_WRITER_H_ -#define CYBERTRON_NODE_WRITER_H_ +#ifndef CYBER_NODE_WRITER_H_ +#define CYBER_NODE_WRITER_H_ #include #include #include -#include "cybertron/common/log.h" -#include "cybertron/node/writer_base.h" -#include "cybertron/proto/topology_change.pb.h" -#include "cybertron/service_discovery/topology_manager.h" -#include "cybertron/transport/transport.h" +#include "cyber/common/log.h" +#include "cyber/node/writer_base.h" +#include "cyber/proto/topology_change.pb.h" +#include "cyber/service_discovery/topology_manager.h" +#include "cyber/transport/transport.h" namespace apollo { -namespace cybertron { +namespace cyber { template class Writer : public WriterBase { @@ -146,7 +146,7 @@ void Writer::OnChannelChange(const proto::ChangeMsg& change_msg) { } } -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_NODE_WRITER_H_ +#endif // CYBER_NODE_WRITER_H_ diff --git a/cybertron/node/writer_base.h b/cyber/node/writer_base.h similarity index 85% rename from cybertron/node/writer_base.h rename to cyber/node/writer_base.h index c1e9abd9f7c..eef83a223e4 100644 --- a/cybertron/node/writer_base.h +++ b/cyber/node/writer_base.h @@ -14,16 +14,16 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_NODE_WRITER_BASE_H_ -#define CYBERTRON_NODE_WRITER_BASE_H_ +#ifndef CYBER_NODE_WRITER_BASE_H_ +#define CYBER_NODE_WRITER_BASE_H_ #include #include -#include "cybertron/proto/role_attributes.pb.h" +#include "cyber/proto/role_attributes.pb.h" namespace apollo { -namespace cybertron { +namespace cyber { class WriterBase { public: @@ -44,7 +44,7 @@ class WriterBase { std::atomic init_; }; -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_NODE_WRITER_BASE_H_ +#endif // CYBER_NODE_WRITER_BASE_H_ diff --git a/cybertron/node/writer_reader_test.cc b/cyber/node/writer_reader_test.cc similarity index 96% rename from cybertron/node/writer_reader_test.cc rename to cyber/node/writer_reader_test.cc index 5528fad9c83..2fbe3e32659 100644 --- a/cybertron/node/writer_reader_test.cc +++ b/cyber/node/writer_reader_test.cc @@ -20,14 +20,14 @@ #include #include -#include "cybertron/common/global_data.h" -#include "cybertron/init.h" -#include "cybertron/node/reader.h" -#include "cybertron/node/writer.h" -#include "cybertron/proto/unit_test.pb.h" +#include "cyber/common/global_data.h" +#include "cyber/init.h" +#include "cyber/node/reader.h" +#include "cyber/node/writer.h" +#include "cyber/proto/unit_test.pb.h" namespace apollo { -namespace cybertron { +namespace cyber { TEST(WriterReaderTest, constructor) { const std::string channel_name("constructor"); @@ -245,5 +245,5 @@ TEST(WriterReaderTest, get_delay_sec) { EXPECT_GT(reader.GetDelaySec(), 1); } -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/parameter/BUILD b/cyber/parameter/BUILD similarity index 81% rename from cybertron/parameter/BUILD rename to cyber/parameter/BUILD index 5a550c60436..708e2d41a63 100644 --- a/cybertron/parameter/BUILD +++ b/cyber/parameter/BUILD @@ -11,8 +11,8 @@ cc_library( "parameter.h", ], deps = [ - "//cybertron/message:protobuf_factory", - "//cybertron/proto:parameter_cc_proto", + "//cyber/message:protobuf_factory", + "//cyber/proto:parameter_cc_proto", ], ) @@ -23,7 +23,7 @@ cc_test( "parameter_test.cc", ], deps = [ - "//cybertron", + "//cyber", "@gtest//:main", ], ) @@ -39,8 +39,8 @@ cc_library( deps = [ "parameter", "parameter_service_names", - "//cybertron/node:node", - "//cybertron/service:client", + "//cyber/node:node", + "//cyber/service:client", "@fastrtps", ] ) @@ -52,7 +52,7 @@ cc_test( "parameter_client_test.cc", ], deps = [ - "//cybertron", + "//cyber", "@gtest//:main", ], ) @@ -68,8 +68,8 @@ cc_library( deps = [ "parameter", "parameter_service_names", - "//cybertron/node:node", - "//cybertron/service:service", + "//cyber/node:node", + "//cyber/service:service", "@fastrtps", ] ) @@ -81,7 +81,7 @@ cc_test( "parameter_server_test.cc", ], deps = [ - "//cybertron", + "//cyber", "@gtest//:main", ], ) diff --git a/cybertron/parameter/parameter.cc b/cyber/parameter/parameter.cc similarity index 96% rename from cybertron/parameter/parameter.cc rename to cyber/parameter/parameter.cc index 4aea9c44684..c9608a894ed 100644 --- a/cybertron/parameter/parameter.cc +++ b/cyber/parameter/parameter.cc @@ -14,13 +14,13 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/parameter/parameter.h" -#include "cybertron/message/protobuf_factory.h" +#include "cyber/parameter/parameter.h" +#include "cyber/message/protobuf_factory.h" namespace apollo { -namespace cybertron { +namespace cyber { -using apollo::cybertron::message::ProtobufFactory; +using apollo::cyber::message::ProtobufFactory; Parameter::Parameter() { param_.set_name(""); @@ -157,5 +157,5 @@ std::string Parameter::DebugString() const { return ss.str(); } -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/parameter/parameter.h b/cyber/parameter/parameter.h similarity index 87% rename from cybertron/parameter/parameter.h rename to cyber/parameter/parameter.h index 6cc0173fa86..02b78ccaf30 100644 --- a/cybertron/parameter/parameter.h +++ b/cyber/parameter/parameter.h @@ -14,20 +14,20 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_PARAMETER_PARAMETER_H_ -#define CYBERTRON_PARAMETER_PARAMETER_H_ +#ifndef CYBER_PARAMETER_PARAMETER_H_ +#define CYBER_PARAMETER_PARAMETER_H_ #include -#include "cybertron/common/log.h" -#include "cybertron/proto/parameter.pb.h" +#include "cyber/common/log.h" +#include "cyber/proto/parameter.pb.h" /** - * @namespace cybertron.parameter + * @namespace cyber.parameter */ namespace apollo { -namespace cybertron { +namespace cyber { -using apollo::cybertron::proto::Param; -using apollo::cybertron::proto::ParamType; +using apollo::cyber::proto::Param; +using apollo::cyber::proto::ParamType; /** * @class Parameter @@ -49,24 +49,24 @@ class Parameter { Parameter(const std::string& name, const google::protobuf::Message& msg); /** - * @brief Parse a cybertron::proto::Param object to - * cybertron::parameter::Parameter object - * @param param The cybertron::proto::Param object parse from + * @brief Parse a cyber::proto::Param object to + * cyber::parameter::Parameter object + * @param param The cyber::proto::Param object parse from * @param parameter A pointer to the target Parameter object * @return True if parse ok, otherwise False */ void FromProtoParam(const Param& param); /** - * @brief Parse a cybertron::parameter::Parameter object to - * cybertron::proto::Param object - * @return The target cybertron::proto::Param object + * @brief Parse a cyber::parameter::Parameter object to + * cyber::proto::Param object + * @return The target cyber::proto::Param object */ Param ToProtoParam() const; /** - * @brief Get the cybertron:parameter::ParameterType of this object - * @return cybertron:parameter::ParameterType + * @brief Get the cyber:parameter::ParameterType of this object + * @return cyber:parameter::ParameterType */ inline ParamType Type() const; inline std::string TypeName() const; @@ -182,7 +182,7 @@ inline double Parameter::AsDouble() const { return value(); } const std::string Parameter::AsString() const { return value(); } -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_PARAMETER_PARAMETER_H_ +#endif // CYBER_PARAMETER_PARAMETER_H_ diff --git a/cybertron/parameter/parameter_client.cc b/cyber/parameter/parameter_client.cc similarity index 93% rename from cybertron/parameter/parameter_client.cc rename to cyber/parameter/parameter_client.cc index 61ffbbed936..71f79018ba2 100644 --- a/cybertron/parameter/parameter_client.cc +++ b/cyber/parameter/parameter_client.cc @@ -14,12 +14,12 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/parameter/parameter_client.h" -#include "cybertron/node/node.h" -#include "cybertron/parameter/parameter_service_names.h" +#include "cyber/parameter/parameter_client.h" +#include "cyber/node/node.h" +#include "cyber/parameter/parameter_service_names.h" namespace apollo { -namespace cybertron { +namespace cyber { ParameterClient::ParameterClient(const std::shared_ptr& node, const std::string& service_node_name) @@ -77,5 +77,5 @@ bool ParameterClient::ListParameters(std::vector* parameters) { return true; } -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/parameter/parameter_client.h b/cyber/parameter/parameter_client.h similarity index 80% rename from cybertron/parameter/parameter_client.h rename to cyber/parameter/parameter_client.h index 6aec2e74b48..343c9ea0c86 100644 --- a/cybertron/parameter/parameter_client.h +++ b/cyber/parameter/parameter_client.h @@ -14,28 +14,28 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_PARAMETER_PARAMETER_CLIENT_H_ -#define CYBERTRON_PARAMETER_PARAMETER_CLIENT_H_ +#ifndef CYBER_PARAMETER_PARAMETER_CLIENT_H_ +#define CYBER_PARAMETER_PARAMETER_CLIENT_H_ #include #include #include -#include "cybertron/parameter/parameter.h" -#include "cybertron/proto/parameter.pb.h" -#include "cybertron/service/client.h" +#include "cyber/parameter/parameter.h" +#include "cyber/proto/parameter.pb.h" +#include "cyber/service/client.h" namespace apollo { -namespace cybertron { +namespace cyber { class Node; class ParameterClient { public: - using Param = apollo::cybertron::proto::Param; - using NodeName = apollo::cybertron::proto::NodeName; - using ParamName = apollo::cybertron::proto::ParamName; - using BoolResult = apollo::cybertron::proto::BoolResult; - using Params = apollo::cybertron::proto::Params; + using Param = apollo::cyber::proto::Param; + using NodeName = apollo::cyber::proto::NodeName; + using ParamName = apollo::cyber::proto::ParamName; + using BoolResult = apollo::cyber::proto::BoolResult; + using Params = apollo::cyber::proto::Params; using GetParameterClient = Client; using SetParameterClient = Client; using ListParametersClient = Client; @@ -85,7 +85,7 @@ class ParameterClient { std::shared_ptr list_parameters_client_; }; -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_PARAMETER_PARAMETER_CLIENT_H_ +#endif // CYBER_PARAMETER_PARAMETER_CLIENT_H_ diff --git a/cybertron/parameter/parameter_client_test.cc b/cyber/parameter/parameter_client_test.cc similarity index 87% rename from cybertron/parameter/parameter_client_test.cc rename to cyber/parameter/parameter_client_test.cc index fc03e00b1b4..88c72488470 100644 --- a/cybertron/parameter/parameter_client_test.cc +++ b/cyber/parameter/parameter_client_test.cc @@ -18,16 +18,16 @@ #include #include -#include "cybertron/cybertron.h" -#include "cybertron/message/protobuf_factory.h" -#include "cybertron/parameter/parameter_client.h" -#include "cybertron/parameter/parameter_server.h" +#include "cyber/cyber.h" +#include "cyber/message/protobuf_factory.h" +#include "cyber/parameter/parameter_client.h" +#include "cyber/parameter/parameter_server.h" namespace apollo { -namespace cybertron { +namespace cyber { -using apollo::cybertron::proto::Param; -using apollo::cybertron::proto::ParamType; +using apollo::cyber::proto::Param; +using apollo::cyber::proto::ParamType; class ParameterClientTest : public ::testing::Test { protected: @@ -40,7 +40,7 @@ class ParameterClientTest : public ::testing::Test { virtual void SetUp() { // Called before every TEST_F(ParameterClientTest, *) - apollo::cybertron::Init(); + apollo::cyber::Init(); node_ = CreateNode("parameter_server"); ps_.reset(new ParameterServer(node_)); pc_.reset(new ParameterClient(node_, "parameter_server")); @@ -86,5 +86,5 @@ TEST_F(ParameterClientTest, list_parameter) { EXPECT_FALSE(pc_->ListParameters(¶meters)); } -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/parameter/parameter_server.cc b/cyber/parameter/parameter_server.cc similarity index 93% rename from cybertron/parameter/parameter_server.cc rename to cyber/parameter/parameter_server.cc index 361562531b5..11b57239f9d 100644 --- a/cybertron/parameter/parameter_server.cc +++ b/cyber/parameter/parameter_server.cc @@ -13,13 +13,13 @@ * See the License for the specific language governing permissions and * limitations under the License. *****************************************************************************/ -#include "cybertron/parameter/parameter_server.h" -#include "cybertron/common/log.h" -#include "cybertron/node/node.h" -#include "cybertron/parameter/parameter_service_names.h" +#include "cyber/parameter/parameter_server.h" +#include "cyber/common/log.h" +#include "cyber/node/node.h" +#include "cyber/parameter/parameter_service_names.h" namespace apollo { -namespace cybertron { +namespace cyber { ParameterServer::ParameterServer(const std::shared_ptr& node) : node_(node) { @@ -82,5 +82,5 @@ void ParameterServer::ListParameters(std::vector* parameters) { } } -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/parameter/parameter_server.h b/cyber/parameter/parameter_server.h similarity index 77% rename from cybertron/parameter/parameter_server.h rename to cyber/parameter/parameter_server.h index 412c22b18b4..a2621abce3b 100644 --- a/cybertron/parameter/parameter_server.h +++ b/cyber/parameter/parameter_server.h @@ -14,29 +14,29 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_PARAMETER_PARAMETER_SERVER_H_ -#define CYBERTRON_PARAMETER_PARAMETER_SERVER_H_ +#ifndef CYBER_PARAMETER_PARAMETER_SERVER_H_ +#define CYBER_PARAMETER_PARAMETER_SERVER_H_ #include #include #include #include -#include "cybertron/parameter/parameter.h" -#include "cybertron/proto/parameter.pb.h" -#include "cybertron/service/service.h" +#include "cyber/parameter/parameter.h" +#include "cyber/proto/parameter.pb.h" +#include "cyber/service/service.h" namespace apollo { -namespace cybertron { +namespace cyber { class Node; class ParameterServer { public: - using Param = apollo::cybertron::proto::Param; - using NodeName = apollo::cybertron::proto::NodeName; - using ParamName = apollo::cybertron::proto::ParamName; - using BoolResult = apollo::cybertron::proto::BoolResult; - using Params = apollo::cybertron::proto::Params; + using Param = apollo::cyber::proto::Param; + using NodeName = apollo::cyber::proto::NodeName; + using ParamName = apollo::cyber::proto::ParamName; + using BoolResult = apollo::cyber::proto::BoolResult; + using Params = apollo::cyber::proto::Params; /** * @brief Construct a new ParameterServer object * @@ -78,7 +78,7 @@ class ParameterServer { std::unordered_map param_map_; }; -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_PARAMETER_PARAMETER_SERVER_H_ +#endif // CYBER_PARAMETER_PARAMETER_SERVER_H_ diff --git a/cybertron/parameter/parameter_server_test.cc b/cyber/parameter/parameter_server_test.cc similarity index 86% rename from cybertron/parameter/parameter_server_test.cc rename to cyber/parameter/parameter_server_test.cc index 7a5638f5055..341bf434211 100644 --- a/cybertron/parameter/parameter_server_test.cc +++ b/cyber/parameter/parameter_server_test.cc @@ -18,15 +18,15 @@ #include #include -#include "cybertron/cybertron.h" -#include "cybertron/message/protobuf_factory.h" -#include "cybertron/parameter/parameter_server.h" +#include "cyber/cyber.h" +#include "cyber/message/protobuf_factory.h" +#include "cyber/parameter/parameter_server.h" namespace apollo { -namespace cybertron { +namespace cyber { -using apollo::cybertron::proto::Param; -using apollo::cybertron::proto::ParamType; +using apollo::cyber::proto::Param; +using apollo::cyber::proto::ParamType; class ParameterServerTest : public ::testing::Test { protected: @@ -38,7 +38,7 @@ class ParameterServerTest : public ::testing::Test { virtual void SetUp() { // Called before every TEST_F(ParameterServerTest, *) - apollo::cybertron::Init(); + apollo::cyber::Init(); node_ = CreateNode("parameter_server"); ps_.reset(new ParameterServer(node_)); } @@ -69,5 +69,5 @@ TEST_F(ParameterServerTest, list_parameter) { EXPECT_EQ(1, parameters[0].AsInt64()); } -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/parameter/parameter_service_names.h b/cyber/parameter/parameter_service_names.h similarity index 86% rename from cybertron/parameter/parameter_service_names.h rename to cyber/parameter/parameter_service_names.h index 73af70e6c87..98018d156ff 100644 --- a/cybertron/parameter/parameter_service_names.h +++ b/cyber/parameter/parameter_service_names.h @@ -14,13 +14,13 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_PARAMETER_PARAMETER_SERVICE_NAMES_H_ -#define CYBERTRON_PARAMETER_PARAMETER_SERVICE_NAMES_H_ +#ifndef CYBER_PARAMETER_PARAMETER_SERVICE_NAMES_H_ +#define CYBER_PARAMETER_PARAMETER_SERVICE_NAMES_H_ #include namespace apollo { -namespace cybertron { +namespace cyber { constexpr auto SERVICE_NAME_DELIMITER = "/"; constexpr auto GET_PARAMETER_SERVICE_NAME = "get_parameter"; @@ -33,7 +33,7 @@ static inline std::string FixParameterServiceName(const std::string& node_name, std::string(service_name); } -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_PARAMETER_PARAMETER_SERVICE_NAMES_H_ +#endif // CYBER_PARAMETER_PARAMETER_SERVICE_NAMES_H_ diff --git a/cybertron/parameter/parameter_test.cc b/cyber/parameter/parameter_test.cc similarity index 91% rename from cybertron/parameter/parameter_test.cc rename to cyber/parameter/parameter_test.cc index 0c99f0fff59..eb2e74a3aae 100644 --- a/cybertron/parameter/parameter_test.cc +++ b/cyber/parameter/parameter_test.cc @@ -17,16 +17,16 @@ #include #include -#include "cybertron/cybertron.h" -#include "cybertron/message/message_traits.h" -#include "cybertron/parameter/parameter.h" -#include "cybertron/proto/parameter.pb.h" +#include "cyber/cyber.h" +#include "cyber/message/message_traits.h" +#include "cyber/parameter/parameter.h" +#include "cyber/proto/parameter.pb.h" namespace apollo { -namespace cybertron { +namespace cyber { -using apollo::cybertron::proto::Param; -using apollo::cybertron::proto::ParamType; +using apollo::cyber::proto::Param; +using apollo::cyber::proto::ParamType; class ParameterTest : public ::testing::Test { protected: @@ -121,7 +121,7 @@ TEST_F(ParameterTest, type_name) { EXPECT_EQ("INT", _int_param->TypeName()); EXPECT_EQ("DOUBLE", _double_param->TypeName()); EXPECT_EQ("STRING", _string_param->TypeName()); - EXPECT_EQ("apollo.cybertron.proto.Param", _protobuf_param->TypeName()); + EXPECT_EQ("apollo.cyber.proto.Param", _protobuf_param->TypeName()); } TEST_F(ParameterTest, name) { @@ -164,7 +164,7 @@ TEST_F(ParameterTest, value) { auto param = _protobuf_param->value(); EXPECT_EQ("protobuf", _protobuf_param->Name()); - EXPECT_EQ("apollo.cybertron.proto.Param", _protobuf_param->TypeName()); + EXPECT_EQ("apollo.cyber.proto.Param", _protobuf_param->TypeName()); std::string str; param.SerializeToString(&str); EXPECT_EQ(str, _protobuf_param->value()); @@ -181,10 +181,10 @@ TEST_F(ParameterTest, debug_string) { EXPECT_EQ("{name: \"string\", type: \"STRING\", value: \"test\"}", _string_param->DebugString()); EXPECT_EQ( - "{name: \"protobuf\", type: \"apollo.cybertron.proto.Param\", value: " + "{name: \"protobuf\", type: \"apollo.cyber.proto.Param\", value: " "\"name: \"param\"\"}", _protobuf_param->DebugString()); } -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/proto/BUILD b/cyber/proto/BUILD similarity index 100% rename from cybertron/proto/BUILD rename to cyber/proto/BUILD diff --git a/cybertron/proto/__init__.py b/cyber/proto/__init__.py similarity index 100% rename from cybertron/proto/__init__.py rename to cyber/proto/__init__.py diff --git a/cybertron/proto/benchmark_dag_config.proto b/cyber/proto/benchmark_dag_config.proto similarity index 96% rename from cybertron/proto/benchmark_dag_config.proto rename to cyber/proto/benchmark_dag_config.proto index d41579e7c4a..8a9612bad12 100644 --- a/cybertron/proto/benchmark_dag_config.proto +++ b/cyber/proto/benchmark_dag_config.proto @@ -1,6 +1,6 @@ syntax = "proto2"; -package apollo.cybertron.proto; +package apollo.cyber.proto; enum BNodeType { START_NODE = 1; diff --git a/cybertron/proto/chatter.proto b/cyber/proto/chatter.proto similarity index 90% rename from cybertron/proto/chatter.proto rename to cyber/proto/chatter.proto index 8a604bbd36b..fadff127ad1 100644 --- a/cybertron/proto/chatter.proto +++ b/cyber/proto/chatter.proto @@ -1,6 +1,6 @@ syntax = "proto2"; -package apollo.cybertron.proto; +package apollo.cyber.proto; message Chatter { optional uint64 timestamp = 1; diff --git a/cybertron/proto/component_config.proto b/cyber/proto/component_config.proto similarity index 89% rename from cybertron/proto/component_config.proto rename to cyber/proto/component_config.proto index 2e432531e6f..ceccdfd2f7a 100644 --- a/cybertron/proto/component_config.proto +++ b/cyber/proto/component_config.proto @@ -1,8 +1,8 @@ syntax = "proto2"; -package apollo.cybertron.proto; +package apollo.cyber.proto; -import "cybertron/proto/qos_profile.proto"; +import "cyber/proto/qos_profile.proto"; message ReaderOption { optional string channel = 1; diff --git a/cyber/proto/cyber_config.proto b/cyber/proto/cyber_config.proto new file mode 100644 index 00000000000..bd98e123a65 --- /dev/null +++ b/cyber/proto/cyber_config.proto @@ -0,0 +1,21 @@ +syntax = "proto2"; + +package apollo.cyber.proto; + +import "cyber/proto/routine_conf.proto"; +import "cyber/proto/scheduler_conf.proto"; +import "cyber/proto/transport_conf.proto"; +import "cyber/proto/log_conf.proto"; +import "cyber/proto/perf_conf.proto"; +import "cyber/proto/run_mode_conf.proto"; +import "cyber/proto/record_conf.proto"; + +message CyberConfig { + optional LogConf log_conf = 1; + optional RoutineConf routine_conf = 2; + optional SchedulerConf scheduler_conf = 3; + optional TransportConf transport_conf = 4; + optional PerfConf perf_conf = 5; + optional RunModeConf run_mode_conf = 6; + optional RecordConf record_conf = 7; +} diff --git a/cybertron/proto/dag_config.proto b/cyber/proto/dag_config.proto similarity index 85% rename from cybertron/proto/dag_config.proto rename to cyber/proto/dag_config.proto index 0366a072408..e18bd0a7c1e 100644 --- a/cybertron/proto/dag_config.proto +++ b/cyber/proto/dag_config.proto @@ -1,8 +1,8 @@ syntax = "proto2"; -package apollo.cybertron.proto; +package apollo.cyber.proto; -import "cybertron/proto/component_config.proto"; +import "cyber/proto/component_config.proto"; message ComponentInfo { optional string class_name = 1; diff --git a/cybertron/proto/driver.proto b/cyber/proto/driver.proto similarity index 92% rename from cybertron/proto/driver.proto rename to cyber/proto/driver.proto index 4980c9cbb5c..96f77b85417 100644 --- a/cybertron/proto/driver.proto +++ b/cyber/proto/driver.proto @@ -1,6 +1,6 @@ syntax = "proto2"; -package apollo.cybertron.proto; +package apollo.cyber.proto; message Driver { message Header { diff --git a/cybertron/proto/log_conf.proto b/cyber/proto/log_conf.proto similarity index 90% rename from cybertron/proto/log_conf.proto rename to cyber/proto/log_conf.proto index bb1cc54d97e..b3a60f91878 100644 --- a/cybertron/proto/log_conf.proto +++ b/cyber/proto/log_conf.proto @@ -1,6 +1,6 @@ syntax = "proto2"; -package apollo.cybertron.proto; +package apollo.cyber.proto; enum LogLevel { DEBUG = -1; diff --git a/cybertron/proto/parameter.proto b/cyber/proto/parameter.proto similarity index 95% rename from cybertron/proto/parameter.proto rename to cyber/proto/parameter.proto index 8a5c92807f4..a6a003fa7f4 100644 --- a/cybertron/proto/parameter.proto +++ b/cyber/proto/parameter.proto @@ -1,6 +1,6 @@ syntax = "proto2"; -package apollo.cybertron.proto; +package apollo.cyber.proto; enum ParamType { NOT_SET = 0; diff --git a/cybertron/proto/perception.proto b/cyber/proto/perception.proto similarity index 86% rename from cybertron/proto/perception.proto rename to cyber/proto/perception.proto index e61ecefa00c..147eaae697d 100644 --- a/cybertron/proto/perception.proto +++ b/cyber/proto/perception.proto @@ -1,6 +1,6 @@ syntax = "proto2"; -package apollo.cybertron.proto; +package apollo.cyber.proto; message Perception { message Header { diff --git a/cybertron/proto/perf_conf.proto b/cyber/proto/perf_conf.proto similarity index 84% rename from cybertron/proto/perf_conf.proto rename to cyber/proto/perf_conf.proto index 413bd4393d9..8cd9a5d7cff 100644 --- a/cybertron/proto/perf_conf.proto +++ b/cyber/proto/perf_conf.proto @@ -1,6 +1,6 @@ syntax = "proto2"; -package apollo.cybertron.proto; +package apollo.cyber.proto; enum PerfType { SCHED = 1; diff --git a/cybertron/proto/proto_desc.proto b/cyber/proto/proto_desc.proto similarity index 77% rename from cybertron/proto/proto_desc.proto rename to cyber/proto/proto_desc.proto index 5c743a77dec..a61ddfa7219 100644 --- a/cybertron/proto/proto_desc.proto +++ b/cyber/proto/proto_desc.proto @@ -1,6 +1,6 @@ syntax = "proto2"; -package apollo.cybertron.proto; +package apollo.cyber.proto; message ProtoDesc { optional bytes desc = 1; diff --git a/cybertron/proto/qos_profile.proto b/cyber/proto/qos_profile.proto similarity index 95% rename from cybertron/proto/qos_profile.proto rename to cyber/proto/qos_profile.proto index 629acf097a5..860b0d8fc4c 100644 --- a/cybertron/proto/qos_profile.proto +++ b/cyber/proto/qos_profile.proto @@ -1,6 +1,6 @@ syntax = "proto2"; -package apollo.cybertron.proto; +package apollo.cyber.proto; enum QosHistoryPolicy { HISTORY_SYSTEM_DEFAULT = 0; diff --git a/cybertron/proto/record.proto b/cyber/proto/record.proto similarity index 98% rename from cybertron/proto/record.proto rename to cyber/proto/record.proto index aba53318477..150ea7e9c06 100644 --- a/cybertron/proto/record.proto +++ b/cyber/proto/record.proto @@ -1,6 +1,6 @@ syntax = "proto2"; -package apollo.cybertron.proto; +package apollo.cyber.proto; enum SectionType { SECTION_HEADER = 0; diff --git a/cybertron/proto/record_conf.proto b/cyber/proto/record_conf.proto similarity index 77% rename from cybertron/proto/record_conf.proto rename to cyber/proto/record_conf.proto index 9e6023dc62b..93c0208feb5 100644 --- a/cybertron/proto/record_conf.proto +++ b/cyber/proto/record_conf.proto @@ -1,6 +1,6 @@ syntax = "proto2"; -package apollo.cybertron.proto; +package apollo.cyber.proto; message RecordConf { optional uint32 reader_pending_queue_size = 1 [default = 50]; diff --git a/cybertron/proto/role_attributes.proto b/cyber/proto/role_attributes.proto similarity index 92% rename from cybertron/proto/role_attributes.proto rename to cyber/proto/role_attributes.proto index db7d6c20c8a..8c060daa44e 100644 --- a/cybertron/proto/role_attributes.proto +++ b/cyber/proto/role_attributes.proto @@ -1,8 +1,8 @@ syntax = "proto2"; -package apollo.cybertron.proto; +package apollo.cyber.proto; -import "cybertron/proto/qos_profile.proto"; +import "cyber/proto/qos_profile.proto"; message SocketAddr { optional string ip = 1; // dotted decimal diff --git a/cybertron/proto/routine_conf.proto b/cyber/proto/routine_conf.proto similarity index 92% rename from cybertron/proto/routine_conf.proto rename to cyber/proto/routine_conf.proto index a3c100af6de..c72ed7cdb91 100644 --- a/cybertron/proto/routine_conf.proto +++ b/cyber/proto/routine_conf.proto @@ -1,6 +1,6 @@ syntax = "proto2"; -package apollo.cybertron.proto; +package apollo.cyber.proto; message RoutineConfInfo { optional string routine_name = 1; diff --git a/cybertron/proto/run_mode_conf.proto b/cyber/proto/run_mode_conf.proto similarity index 83% rename from cybertron/proto/run_mode_conf.proto rename to cyber/proto/run_mode_conf.proto index 997b433d744..edc38fd93c4 100644 --- a/cybertron/proto/run_mode_conf.proto +++ b/cyber/proto/run_mode_conf.proto @@ -1,6 +1,6 @@ syntax = "proto2"; -package apollo.cybertron.proto; +package apollo.cyber.proto; enum RunMode { MODE_REALITY = 0; diff --git a/cybertron/proto/scheduler_conf.proto b/cyber/proto/scheduler_conf.proto similarity index 93% rename from cybertron/proto/scheduler_conf.proto rename to cyber/proto/scheduler_conf.proto index bb6f92cdd3e..51ba55e1851 100644 --- a/cybertron/proto/scheduler_conf.proto +++ b/cyber/proto/scheduler_conf.proto @@ -1,6 +1,6 @@ syntax = "proto2"; -package apollo.cybertron.proto; +package apollo.cyber.proto; enum ProcessStrategy { CLASSIC = 0; diff --git a/cybertron/proto/topology_change.proto b/cyber/proto/topology_change.proto similarity index 87% rename from cybertron/proto/topology_change.proto rename to cyber/proto/topology_change.proto index 1f467d09577..ac2cfd07283 100644 --- a/cybertron/proto/topology_change.proto +++ b/cyber/proto/topology_change.proto @@ -1,8 +1,8 @@ syntax = "proto2"; -package apollo.cybertron.proto; +package apollo.cyber.proto; -import "cybertron/proto/role_attributes.proto"; +import "cyber/proto/role_attributes.proto"; enum ChangeType { CHANGE_NODE = 1; diff --git a/cybertron/proto/transport_conf.proto b/cyber/proto/transport_conf.proto similarity index 96% rename from cybertron/proto/transport_conf.proto rename to cyber/proto/transport_conf.proto index 1b7320684bc..554abae0e32 100644 --- a/cybertron/proto/transport_conf.proto +++ b/cyber/proto/transport_conf.proto @@ -1,6 +1,6 @@ syntax = "proto2"; -package apollo.cybertron.proto; +package apollo.cyber.proto; enum OptionalMode { HYBRID = 0; diff --git a/cybertron/proto/unit_test.proto b/cyber/proto/unit_test.proto similarity index 77% rename from cybertron/proto/unit_test.proto rename to cyber/proto/unit_test.proto index dd5d501600d..1cdf1fca826 100644 --- a/cybertron/proto/unit_test.proto +++ b/cyber/proto/unit_test.proto @@ -1,6 +1,6 @@ syntax = "proto2"; -package apollo.cybertron.proto; +package apollo.cyber.proto; message UnitTest { optional string class_name = 1; diff --git a/cyber/py_wrapper/BUILD b/cyber/py_wrapper/BUILD new file mode 100644 index 00000000000..fda2fd045be --- /dev/null +++ b/cyber/py_wrapper/BUILD @@ -0,0 +1,63 @@ +load("//tools:cpplint.bzl", "cpplint") + +package(default_visibility = ["//visibility:public"]) + +cc_binary( + name = "_cyber_init.so", + deps = [ + ":py_init", + ], + linkshared = True, + linkstatic = False, +) + +cc_library( + name = "py_init", + srcs = [ "cyber_init_wrap.cc", ], + hdrs = [ "py_init.h", ], + deps = [ + "//cyber:cyber_core", + "@python27", + ], +) + +cc_binary( + name = "_cyber_node.so", + deps = [ + ":py_node", + ], + linkshared = True, + linkstatic = False, +) + +cc_library( + name = "py_node", + srcs = [ "cyber_node_wrap.cc", ], + hdrs = [ "py_node.h", ], + deps = [ + "//cyber:cyber_core", + "@python27", + ], +) + +cc_binary( + name = "_cyber_record.so", + deps = [ + ":py_record", + ], + linkshared = True, + linkstatic = False, +) + +cc_library( + name = "py_record", + srcs = [ "cyber_record_wrap.cc", ], + hdrs = [ "py_record.h", ], + deps = [ + "//cyber:cyber_core", + "//cyber/record", + "@python27", + ], +) + +cpplint() diff --git a/cybertron/py_wrapper/cyber_init_wrap.cc b/cyber/py_wrapper/cyber_init_wrap.cc similarity index 88% rename from cybertron/py_wrapper/cyber_init_wrap.cc rename to cyber/py_wrapper/cyber_init_wrap.cc index 35f94270de9..1b0597508cd 100644 --- a/cybertron/py_wrapper/cyber_init_wrap.cc +++ b/cyber/py_wrapper/cyber_init_wrap.cc @@ -17,10 +17,10 @@ #include #include -#include "cybertron/py_wrapper/py_init.h" +#include "cyber/py_wrapper/py_init.h" static PyObject *cyber_py_init(PyObject *self, PyObject *args) { - bool is_init = apollo::cybertron::py_init(); + bool is_init = apollo::cyber::py_init(); if (is_init) { Py_RETURN_TRUE; } else { @@ -29,7 +29,7 @@ static PyObject *cyber_py_init(PyObject *self, PyObject *args) { } static PyObject *cyber_py_ok(PyObject *self, PyObject *args) { - bool is_ok = apollo::cybertron::py_ok(); + bool is_ok = apollo::cyber::py_ok(); if (is_ok) { Py_RETURN_TRUE; } else { @@ -38,12 +38,12 @@ static PyObject *cyber_py_ok(PyObject *self, PyObject *args) { } static PyObject *cyber_py_shutdown(PyObject *self, PyObject *args) { - apollo::cybertron::py_shutdown(); + apollo::cyber::py_shutdown(); return Py_None; } static PyObject *cyber_py_is_shutdown(PyObject *self, PyObject *args) { - bool is_shutdown = apollo::cybertron::py_is_shutdown(); + bool is_shutdown = apollo::cyber::py_is_shutdown(); if (is_shutdown) { Py_RETURN_TRUE; } else { @@ -52,7 +52,7 @@ static PyObject *cyber_py_is_shutdown(PyObject *self, PyObject *args) { } static PyObject *cyber_py_waitforshutdown(PyObject *self, PyObject *args) { - apollo::cybertron::py_waitforshutdown(); + apollo::cyber::py_waitforshutdown(); return Py_None; } diff --git a/cybertron/py_wrapper/cyber_node_wrap.cc b/cyber/py_wrapper/cyber_node_wrap.cc similarity index 79% rename from cybertron/py_wrapper/cyber_node_wrap.cc rename to cyber/py_wrapper/cyber_node_wrap.cc index d8092bb18ce..1594d59a0cd 100644 --- a/cybertron/py_wrapper/cyber_node_wrap.cc +++ b/cyber/py_wrapper/cyber_node_wrap.cc @@ -18,10 +18,10 @@ #include #include -#include "cybertron/py_wrapper/py_node.h" +#include "cyber/py_wrapper/py_node.h" static PyObject *cyber_py_is_shutdown(PyObject *self, PyObject *args) { - bool is_shutdown = apollo::cybertron::py_is_shutdown(); + bool is_shutdown = apollo::cyber::py_is_shutdown(); if (is_shutdown) { Py_RETURN_TRUE; } else { @@ -30,7 +30,7 @@ static PyObject *cyber_py_is_shutdown(PyObject *self, PyObject *args) { } static PyObject *cyber_py_init(PyObject *self, PyObject *args) { - bool is_init = apollo::cybertron::py_init(); + bool is_init = apollo::cyber::py_init(); if (is_init) { Py_RETURN_TRUE; } else { @@ -39,7 +39,7 @@ static PyObject *cyber_py_init(PyObject *self, PyObject *args) { } static PyObject *cyber_py_ok(PyObject *self, PyObject *args) { - bool is_ok = apollo::cybertron::OK(); + bool is_ok = apollo::cyber::OK(); if (is_ok) { Py_RETURN_TRUE; } else { @@ -62,7 +62,7 @@ PyObject *cyber_new_PyWriter(PyObject *self, PyObject *args) { char *channel_name = nullptr; char *data_type = nullptr; uint32_t qos_depth = 1; - apollo::cybertron::Node *node = nullptr; + apollo::cyber::Node *node = nullptr; PyObject *node_pyobj = nullptr; if (!PyArg_ParseTuple(args, const_cast("ssIO:new_PyWriter"), @@ -70,23 +70,23 @@ PyObject *cyber_new_PyWriter(PyObject *self, PyObject *args) { return Py_None; } - node = (apollo::cybertron::Node *)PyCapsule_GetPointer( - node_pyobj, "apollo_cybertron_pynode"); + node = (apollo::cyber::Node *)PyCapsule_GetPointer( + node_pyobj, "apollo_cyber_pynode"); if (nullptr == node) { AINFO << "node is null"; return Py_None; } - apollo::cybertron::PyWriter *writer = new apollo::cybertron::PyWriter( + apollo::cyber::PyWriter *writer = new apollo::cyber::PyWriter( (std::string const &)*channel_name, (std::string const &)*data_type, qos_depth, node); PyObject *pyobj_writer = - PyCapsule_New(writer, "apollo_cybertron_pywriter", NULL); + PyCapsule_New(writer, "apollo_cyber_pywriter", NULL); return pyobj_writer; } PyObject *cyber_delete_PyWriter(PyObject *self, PyObject *args) { - apollo::cybertron::PyWriter *writer = nullptr; + apollo::cyber::PyWriter *writer = nullptr; PyObject *writer_py = nullptr; if (!PyArg_ParseTuple(args, const_cast("O:delete_PyWriter"), @@ -94,8 +94,8 @@ PyObject *cyber_delete_PyWriter(PyObject *self, PyObject *args) { return Py_None; } - writer = (apollo::cybertron::PyWriter *)PyCapsule_GetPointer( - writer_py, "apollo_cybertron_pywriter"); + writer = (apollo::cyber::PyWriter *)PyCapsule_GetPointer( + writer_py, "apollo_cyber_pywriter"); delete writer; return Py_None; } @@ -110,9 +110,9 @@ PyObject *cyber_PyWriter_write(PyObject *self, PyObject *args) { return PyInt_FromLong(1); } - apollo::cybertron::PyWriter *writer = - PyObjectToPtr(pyobj_writer, - "apollo_cybertron_pywriter"); + apollo::cyber::PyWriter *writer = + PyObjectToPtr(pyobj_writer, + "apollo_cyber_pywriter"); if (nullptr == writer) { AINFO << "cyber_PyWriter_write:writer ptr is null!"; @@ -127,7 +127,7 @@ PyObject *cyber_PyWriter_write(PyObject *self, PyObject *args) { PyObject *cyber_new_PyReader(PyObject *self, PyObject *args) { char *channel_name = nullptr; char *data_type = nullptr; - apollo::cybertron::Node *node = 0; + apollo::cyber::Node *node = 0; PyObject *node_pyobj = 0; if (!PyArg_ParseTuple(args, const_cast("ssO:new_PyReader"), @@ -135,18 +135,18 @@ PyObject *cyber_new_PyReader(PyObject *self, PyObject *args) { return Py_None; } - node = (apollo::cybertron::Node *)PyCapsule_GetPointer( - node_pyobj, "apollo_cybertron_pynode"); + node = (apollo::cyber::Node *)PyCapsule_GetPointer( + node_pyobj, "apollo_cyber_pynode"); if (!node) { AINFO << "node is null"; return Py_None; } - apollo::cybertron::PyReader *reader = - new apollo::cybertron::PyReader((std::string const &)*channel_name, + apollo::cyber::PyReader *reader = + new apollo::cyber::PyReader((std::string const &)*channel_name, (std::string const &)*data_type, node); PyObject *pyobj_reader = - PyCapsule_New(reader, "apollo_cybertron_pyreader", NULL); + PyCapsule_New(reader, "apollo_cyber_pyreader", NULL); return pyobj_reader; } @@ -157,9 +157,9 @@ PyObject *cyber_delete_PyReader(PyObject *self, PyObject *args) { return Py_None; } - apollo::cybertron::PyReader *reader = - (apollo::cybertron::PyReader *)PyCapsule_GetPointer( - reader_py, "apollo_cybertron_pyreader"); + apollo::cyber::PyReader *reader = + (apollo::cyber::PyReader *)PyCapsule_GetPointer( + reader_py, "apollo_cyber_pyreader"); delete reader; return Py_None; } @@ -173,9 +173,9 @@ PyObject *cyber_PyReader_read(PyObject *self, PyObject *args) { AINFO << "cyber_PyReader_read:PyArg_ParseTuple failed!"; return Py_None; } - apollo::cybertron::PyReader *reader = - PyObjectToPtr(pyobj_reader, - "apollo_cybertron_pyreader"); + apollo::cyber::PyReader *reader = + PyObjectToPtr(pyobj_reader, + "apollo_cyber_pyreader"); if (nullptr == reader) { AINFO << "cyber_PyReader_read:PyReader ptr is null!"; return Py_None; @@ -205,9 +205,9 @@ PyObject *cyber_PyReader_register_func(PyObject *self, PyObject *args) { return Py_None; } - apollo::cybertron::PyReader *reader = - PyObjectToPtr(pyobj_reader, - "apollo_cybertron_pyreader"); + apollo::cyber::PyReader *reader = + PyObjectToPtr(pyobj_reader, + "apollo_cyber_pyreader"); callback_fun = (int (*)(const char *i))PyInt_AsLong(pyobj_regist_fun); if (reader) { AINFO << "reader regist fun"; @@ -220,7 +220,7 @@ PyObject *cyber_PyReader_register_func(PyObject *self, PyObject *args) { PyObject *cyber_new_PyClient(PyObject *self, PyObject *args) { char *channel_name = 0; char *data_type = 0; - apollo::cybertron::Node *node = 0; + apollo::cyber::Node *node = 0; PyObject *node_pyobj = 0; if (!PyArg_ParseTuple(args, const_cast("ssO:new_PyClient"), @@ -228,18 +228,18 @@ PyObject *cyber_new_PyClient(PyObject *self, PyObject *args) { return Py_None; } - node = (apollo::cybertron::Node *)PyCapsule_GetPointer( - node_pyobj, "apollo_cybertron_pynode"); + node = (apollo::cyber::Node *)PyCapsule_GetPointer( + node_pyobj, "apollo_cyber_pynode"); if (!node) { AINFO << "node is null"; return Py_None; } - apollo::cybertron::PyClient *client = - new apollo::cybertron::PyClient((std::string const &)*channel_name, + apollo::cyber::PyClient *client = + new apollo::cyber::PyClient((std::string const &)*channel_name, (std::string const &)*data_type, node); PyObject *pyobj_client = - PyCapsule_New(client, "apollo_cybertron_pyclient", NULL); + PyCapsule_New(client, "apollo_cyber_pyclient", NULL); return pyobj_client; } @@ -250,9 +250,9 @@ PyObject *cyber_delete_PyClient(PyObject *self, PyObject *args) { return Py_None; } - apollo::cybertron::PyClient *client = - (apollo::cybertron::PyClient *)PyCapsule_GetPointer( - client_py, "apollo_cybertron_pyclient"); + apollo::cyber::PyClient *client = + (apollo::cyber::PyClient *)PyCapsule_GetPointer( + client_py, "apollo_cyber_pyclient"); delete client; return Py_None; } @@ -267,9 +267,9 @@ PyObject *cyber_PyClient_send_request(PyObject *self, PyObject *args) { return PYOBJECT_NULL_STRING; } - apollo::cybertron::PyClient *client = - PyObjectToPtr(pyobj_client, - "apollo_cybertron_pyclient"); + apollo::cyber::PyClient *client = + PyObjectToPtr(pyobj_client, + "apollo_cyber_pyclient"); if (nullptr == client) { AINFO << "cyber_PyClient_send_request:client ptr is null!"; @@ -287,7 +287,7 @@ PyObject *cyber_PyClient_send_request(PyObject *self, PyObject *args) { PyObject *cyber_new_PyService(PyObject *self, PyObject *args) { char *channel_name = 0; char *data_type = 0; - apollo::cybertron::Node *node = 0; + apollo::cyber::Node *node = 0; PyObject *node_pyobj = 0; if (!PyArg_ParseTuple(args, const_cast("ssO:new_PyService"), @@ -295,18 +295,18 @@ PyObject *cyber_new_PyService(PyObject *self, PyObject *args) { return Py_None; } - node = (apollo::cybertron::Node *)PyCapsule_GetPointer( - node_pyobj, "apollo_cybertron_pynode"); + node = (apollo::cyber::Node *)PyCapsule_GetPointer( + node_pyobj, "apollo_cyber_pynode"); if (!node) { AINFO << "node is null"; return Py_None; } - apollo::cybertron::PyService *service = - new apollo::cybertron::PyService((std::string const &)*channel_name, + apollo::cyber::PyService *service = + new apollo::cyber::PyService((std::string const &)*channel_name, (std::string const &)*data_type, node); PyObject *pyobj_service = - PyCapsule_New(service, "apollo_cybertron_pyservice", NULL); + PyCapsule_New(service, "apollo_cyber_pyservice", NULL); return pyobj_service; } @@ -317,9 +317,9 @@ PyObject *cyber_delete_PyService(PyObject *self, PyObject *args) { return Py_None; } - apollo::cybertron::PyService *service = - (apollo::cybertron::PyService *)PyCapsule_GetPointer( - pyobj_service, "apollo_cybertron_pyservice"); + apollo::cyber::PyService *service = + (apollo::cyber::PyService *)PyCapsule_GetPointer( + pyobj_service, "apollo_cyber_pyservice"); delete service; return Py_None; } @@ -335,9 +335,9 @@ PyObject *cyber_PyService_register_func(PyObject *self, PyObject *args) { return Py_None; } - apollo::cybertron::PyService *service = - PyObjectToPtr( - pyobj_service, "apollo_cybertron_pyservice"); + apollo::cyber::PyService *service = + PyObjectToPtr( + pyobj_service, "apollo_cyber_pyservice"); callback_fun = (int (*)(const char *i))PyInt_AsLong(pyobj_regist_fun); if (service) { AINFO << "service regist fun"; @@ -354,9 +354,9 @@ PyObject *cyber_PyService_read(PyObject *self, PyObject *args) { AINFO << "cyber_PyService_read:PyArg_ParseTuple failed!"; return PYOBJECT_NULL_STRING; } - apollo::cybertron::PyService *service = - PyObjectToPtr( - pyobj_service, "apollo_cybertron_pyservice"); + apollo::cyber::PyService *service = + PyObjectToPtr( + pyobj_service, "apollo_cyber_pyservice"); if (nullptr == service) { AINFO << "cyber_PyService_read:service ptr is null!"; return PYOBJECT_NULL_STRING; @@ -377,9 +377,9 @@ PyObject *cyber_PyService_write(PyObject *self, PyObject *args) { return PyInt_FromLong(1); } - apollo::cybertron::PyService *service = - PyObjectToPtr( - pyobj_service, "apollo_cybertron_pyservice"); + apollo::cyber::PyService *service = + PyObjectToPtr( + pyobj_service, "apollo_cyber_pyservice"); if (nullptr == service) { AINFO << "cyber_PyService_write:writer ptr is null!"; @@ -398,9 +398,9 @@ PyObject *cyber_new_PyNode(PyObject *self, PyObject *args) { return Py_None; } - apollo::cybertron::PyNode *node = - new apollo::cybertron::PyNode((std::string const &)node_name); - PyObject *pyobj_node = PyCapsule_New(node, "apollo_cybertron_pynode", NULL); + apollo::cyber::PyNode *node = + new apollo::cyber::PyNode((std::string const &)node_name); + PyObject *pyobj_node = PyCapsule_New(node, "apollo_cyber_pynode", NULL); return pyobj_node; } @@ -411,9 +411,9 @@ PyObject *cyber_delete_PyNode(PyObject *self, PyObject *args) { return Py_None; } - apollo::cybertron::PyNode *node = - (apollo::cybertron::PyNode *)PyCapsule_GetPointer( - pyobj_node, "apollo_cybertron_pynode"); + apollo::cyber::PyNode *node = + (apollo::cyber::PyNode *)PyCapsule_GetPointer( + pyobj_node, "apollo_cyber_pynode"); delete node; return Py_None; } @@ -430,15 +430,15 @@ PyObject *cyber_PyNode_create_writer(PyObject *self, PyObject *args) { return Py_None; } - apollo::cybertron::PyNode *node = PyObjectToPtr( - pyobj_node, "apollo_cybertron_pynode"); + apollo::cyber::PyNode *node = PyObjectToPtr( + pyobj_node, "apollo_cyber_pynode"); if (nullptr == node) { AINFO << "cyber_PyNode_create_writer:node ptr is null!"; return Py_None; } - apollo::cybertron::PyWriter *writer = - (apollo::cybertron::PyWriter *)(node->create_writer( + apollo::cyber::PyWriter *writer = + (apollo::cyber::PyWriter *)(node->create_writer( (std::string const &)channel_name, (std::string const &)type_name, qos_depth)); @@ -447,7 +447,7 @@ PyObject *cyber_PyNode_create_writer(PyObject *self, PyObject *args) { return Py_None; } PyObject *pyobj_writer = - PyCapsule_New(writer, "apollo_cybertron_pywriter", NULL); + PyCapsule_New(writer, "apollo_cyber_pywriter", NULL); return pyobj_writer; } @@ -462,19 +462,19 @@ PyObject *cyber_PyNode_create_reader(PyObject *self, PyObject *args) { return Py_None; } - apollo::cybertron::PyNode *node = PyObjectToPtr( - pyobj_node, "apollo_cybertron_pynode"); + apollo::cyber::PyNode *node = PyObjectToPtr( + pyobj_node, "apollo_cyber_pynode"); if (nullptr == node) { AINFO << "PyNode_create_reader:node ptr is null!"; return Py_None; } - apollo::cybertron::PyReader *reader = - (apollo::cybertron::PyReader *)(node->create_reader( + apollo::cyber::PyReader *reader = + (apollo::cyber::PyReader *)(node->create_reader( (std::string const &)channel_name, (std::string const &)type_name)); PyObject *pyobj_reader = - PyCapsule_New(reader, "apollo_cybertron_pyreader", NULL); + PyCapsule_New(reader, "apollo_cyber_pyreader", NULL); return pyobj_reader; } @@ -489,18 +489,18 @@ PyObject *cyber_PyNode_create_client(PyObject *self, PyObject *args) { return Py_None; } - apollo::cybertron::PyNode *node = PyObjectToPtr( - pyobj_node, "apollo_cybertron_pynode"); + apollo::cyber::PyNode *node = PyObjectToPtr( + pyobj_node, "apollo_cyber_pynode"); if (nullptr == node) { AINFO << "PyNode_create_client:node ptr is null!"; return Py_None; } - apollo::cybertron::PyClient *client = - (apollo::cybertron::PyClient *)(node->create_client( + apollo::cyber::PyClient *client = + (apollo::cyber::PyClient *)(node->create_client( (std::string const &)channel_name, (std::string const &)type_name)); PyObject *pyobj_client = - PyCapsule_New(client, "apollo_cybertron_pyclient", NULL); + PyCapsule_New(client, "apollo_cyber_pyclient", NULL); return pyobj_client; } @@ -517,18 +517,18 @@ PyObject *cyber_PyNode_create_service(PyObject *self, PyObject *args) { return Py_None; } - apollo::cybertron::PyNode *node = PyObjectToPtr( - pyobj_node, "apollo_cybertron_pynode"); + apollo::cyber::PyNode *node = PyObjectToPtr( + pyobj_node, "apollo_cyber_pynode"); if (nullptr == node) { AINFO << "cyber_PyNode_create_service:node ptr is null!"; return Py_None; } - apollo::cybertron::PyService *service = - (apollo::cybertron::PyService *)(node->create_service( + apollo::cyber::PyService *service = + (apollo::cyber::PyService *)(node->create_service( (std::string const &)channel_name, (std::string const &)type_name)); PyObject *pyobj_service = - PyCapsule_New(service, "apollo_cybertron_pyservice", NULL); + PyCapsule_New(service, "apollo_cyber_pyservice", NULL); return pyobj_service; } @@ -541,8 +541,8 @@ PyObject *cyber_PyNode_shutdown(PyObject *self, PyObject *args) { return Py_None; } - apollo::cybertron::PyNode *node = PyObjectToPtr( - pyobj_node, "apollo_cybertron_pynode"); + apollo::cyber::PyNode *node = PyObjectToPtr( + pyobj_node, "apollo_cyber_pynode"); if (nullptr == node) { AINFO << "cyber_PyNode_shutdown:node ptr is null!"; return Py_None; @@ -561,8 +561,8 @@ PyObject *cyber_PyNode_register_message(PyObject *self, PyObject *args) { AINFO << "cyber_PyNode_register_message: failed!"; return Py_None; } - apollo::cybertron::PyNode *node = PyObjectToPtr( - pyobj_node, "apollo_cybertron_pynode"); + apollo::cyber::PyNode *node = PyObjectToPtr( + pyobj_node, "apollo_cyber_pynode"); if (nullptr == node) { AINFO << "cyber_PyNode_register_message:node ptr is null! desc->" << desc; return Py_None; diff --git a/cybertron/py_wrapper/cyber_record_wrap.cc b/cyber/py_wrapper/cyber_record_wrap.cc similarity index 84% rename from cybertron/py_wrapper/cyber_record_wrap.cc rename to cyber/py_wrapper/cyber_record_wrap.cc index 6555f5b0a9b..6634e6d0219 100644 --- a/cybertron/py_wrapper/cyber_record_wrap.cc +++ b/cyber/py_wrapper/cyber_record_wrap.cc @@ -18,7 +18,7 @@ #include #include -#include "cybertron/py_wrapper/py_record.h" +#include "cyber/py_wrapper/py_record.h" #define PYOBJECT_NULL_STRING PyString_FromStringAndSize("", 0) @@ -40,10 +40,10 @@ PyObject *cyber_new_PyRecordReader(PyObject *self, PyObject *args) { return Py_None; } - apollo::cybertron::record::PyRecordReader *reader = - new apollo::cybertron::record::PyRecordReader(std::string(filepath, len)); + apollo::cyber::record::PyRecordReader *reader = + new apollo::cyber::record::PyRecordReader(std::string(filepath, len)); PyObject *pyobj_rec_reader = - PyCapsule_New(reader, "apollo_cybertron_record_pyrecordfilereader", NULL); + PyCapsule_New(reader, "apollo_cyber_record_pyrecordfilereader", NULL); return pyobj_rec_reader; } @@ -55,8 +55,8 @@ PyObject *cyber_delete_PyRecordReader(PyObject *self, PyObject *args) { } auto reader = - (apollo::cybertron::record::PyRecordReader *)PyCapsule_GetPointer( - pyobj_rec_reader, "apollo_cybertron_record_pyrecordfilereader"); + (apollo::cyber::record::PyRecordReader *)PyCapsule_GetPointer( + pyobj_rec_reader, "apollo_cyber_record_pyrecordfilereader"); if (nullptr == reader) { AINFO << "delete_PyRecordReader:reader ptr is null!"; return Py_None; @@ -76,14 +76,14 @@ PyObject *cyber_PyRecordReader_ReadMessage(PyObject *self, PyObject *args) { } auto reader = - (apollo::cybertron::record::PyRecordReader *)PyCapsule_GetPointer( - pyobj_reader, "apollo_cybertron_record_pyrecordfilereader"); + (apollo::cyber::record::PyRecordReader *)PyCapsule_GetPointer( + pyobj_reader, "apollo_cyber_record_pyrecordfilereader"); if (nullptr == reader) { AERROR << "PyRecordReader_ReadMessage ptr is null!"; return nullptr; } - apollo::cybertron::record::BagMessage result; + apollo::cyber::record::BagMessage result; result = reader->ReadMessage(begin_time, end_time); PyObject *pyobj_bag_message = PyDict_New(); PyDict_SetItemString(pyobj_bag_message, "channel_name", @@ -113,8 +113,8 @@ PyObject *cyber_PyRecordReader_GetMessageNumber(PyObject *self, } auto reader = - (apollo::cybertron::record::PyRecordReader *)PyCapsule_GetPointer( - pyobj_reader, "apollo_cybertron_record_pyrecordfilereader"); + (apollo::cyber::record::PyRecordReader *)PyCapsule_GetPointer( + pyobj_reader, "apollo_cyber_record_pyrecordfilereader"); if (nullptr == reader) { AINFO << "PyRecordReader_GetMessageNumber ptr is null!"; return PyLong_FromUnsignedLongLong(0); @@ -135,8 +135,8 @@ PyObject *cyber_PyRecordReader_GetMessageType(PyObject *self, PyObject *args) { } auto reader = - (apollo::cybertron::record::PyRecordReader *)PyCapsule_GetPointer( - pyobj_reader, "apollo_cybertron_record_pyrecordfilereader"); + (apollo::cyber::record::PyRecordReader *)PyCapsule_GetPointer( + pyobj_reader, "apollo_cyber_record_pyrecordfilereader"); if (nullptr == reader) { AINFO << "PyRecordReader_GetMessageType ptr is null!"; return PYOBJECT_NULL_STRING; @@ -157,8 +157,8 @@ PyObject *cyber_PyRecordReader_GetProtoDesc(PyObject *self, PyObject *args) { } auto reader = - (apollo::cybertron::record::PyRecordReader *)PyCapsule_GetPointer( - pyobj_reader, "apollo_cybertron_record_pyrecordfilereader"); + (apollo::cyber::record::PyRecordReader *)PyCapsule_GetPointer( + pyobj_reader, "apollo_cyber_record_pyrecordfilereader"); if (nullptr == reader) { AINFO << "PyRecordReader_GetProtoDesc ptr is null!"; return PYOBJECT_NULL_STRING; @@ -177,8 +177,8 @@ PyObject *cyber_PyRecordReader_GetHeaderString(PyObject *self, PyObject *args) { } auto reader = - (apollo::cybertron::record::PyRecordReader *)PyCapsule_GetPointer( - pyobj_reader, "apollo_cybertron_record_pyrecordfilereader"); + (apollo::cyber::record::PyRecordReader *)PyCapsule_GetPointer( + pyobj_reader, "apollo_cyber_record_pyrecordfilereader"); if (nullptr == reader) { AINFO << "PyRecordReader_GetHeaderString ptr is null!"; return PYOBJECT_NULL_STRING; @@ -199,8 +199,8 @@ PyObject *cyber_PyRecordReader_Reset(PyObject *self, PyObject *args) { } auto reader = - (apollo::cybertron::record::PyRecordReader *)PyCapsule_GetPointer( - pyobj_reader, "apollo_cybertron_record_pyrecordfilereader"); + (apollo::cyber::record::PyRecordReader *)PyCapsule_GetPointer( + pyobj_reader, "apollo_cyber_record_pyrecordfilereader"); if (nullptr == reader) { AERROR << "PyRecordReader_Reset reader is null!"; return Py_None; @@ -220,8 +220,8 @@ PyObject *cyber_PyRecordReader_GetChannelList(PyObject *self, PyObject *args) { } auto reader = - (apollo::cybertron::record::PyRecordReader *)PyCapsule_GetPointer( - pyobj_reader, "apollo_cybertron_record_pyrecordfilereader"); + (apollo::cyber::record::PyRecordReader *)PyCapsule_GetPointer( + pyobj_reader, "apollo_cyber_record_pyrecordfilereader"); if (nullptr == reader) { AERROR << "PyRecordReader_GetChannelList reader is null!"; return Py_None; @@ -239,10 +239,10 @@ PyObject *cyber_PyRecordReader_GetChannelList(PyObject *self, PyObject *args) { } PyObject *cyber_new_PyRecordWriter(PyObject *self, PyObject *args) { - apollo::cybertron::record::PyRecordWriter *writer = - new apollo::cybertron::record::PyRecordWriter(); + apollo::cyber::record::PyRecordWriter *writer = + new apollo::cyber::record::PyRecordWriter(); PyObject *pyobj_rec_writer = - PyCapsule_New(writer, "apollo_cybertron_record_pyrecordfilewriter", NULL); + PyCapsule_New(writer, "apollo_cyber_record_pyrecordfilewriter", NULL); return pyobj_rec_writer; } @@ -254,8 +254,8 @@ PyObject *cyber_delete_PyRecordWriter(PyObject *self, PyObject *args) { } auto writer = - (apollo::cybertron::record::PyRecordWriter *)PyCapsule_GetPointer( - pyobj_rec_writer, "apollo_cybertron_record_pyrecordfilewriter"); + (apollo::cyber::record::PyRecordWriter *)PyCapsule_GetPointer( + pyobj_rec_writer, "apollo_cyber_record_pyrecordfilewriter"); if (nullptr == writer) { AERROR << "delete_PyRecordWriter:writer is null!"; return Py_None; @@ -275,9 +275,9 @@ PyObject *cyber_PyRecordWriter_Open(PyObject *self, PyObject *args) { Py_RETURN_FALSE; } - apollo::cybertron::record::PyRecordWriter *writer = - PyObjectToPtr( - pyobj_rec_writer, "apollo_cybertron_record_pyrecordfilewriter"); + apollo::cyber::record::PyRecordWriter *writer = + PyObjectToPtr( + pyobj_rec_writer, "apollo_cyber_record_pyrecordfilewriter"); if (nullptr == writer) { AERROR << "PyRecordWriter_Open:writer is null!"; @@ -299,8 +299,8 @@ PyObject *cyber_PyRecordWriter_Close(PyObject *self, PyObject *args) { } auto writer = - (apollo::cybertron::record::PyRecordWriter *)PyCapsule_GetPointer( - pyobj_rec_writer, "apollo_cybertron_record_pyrecordfilewriter"); + (apollo::cyber::record::PyRecordWriter *)PyCapsule_GetPointer( + pyobj_rec_writer, "apollo_cyber_record_pyrecordfilewriter"); if (nullptr == writer) { AERROR << "cyber_PyRecordWriterer_Close: writer is null!"; return Py_None; @@ -322,8 +322,8 @@ PyObject *cyber_PyRecordWriter_WriteChannel(PyObject *self, PyObject *args) { Py_RETURN_FALSE; } - auto writer = PyObjectToPtr( - pyobj_rec_writer, "apollo_cybertron_record_pyrecordfilewriter"); + auto writer = PyObjectToPtr( + pyobj_rec_writer, "apollo_cyber_record_pyrecordfilewriter"); if (nullptr == writer) { AINFO << "cyber_PyRecordWriter_WriteChannel:writer ptr is null!"; @@ -354,8 +354,8 @@ PyObject *cyber_PyRecordWriter_WriteMessage(PyObject *self, PyObject *args) { Py_RETURN_FALSE; } - auto writer = PyObjectToPtr( - pyobj_rec_writer, "apollo_cybertron_record_pyrecordfilewriter"); + auto writer = PyObjectToPtr( + pyobj_rec_writer, "apollo_cyber_record_pyrecordfilewriter"); if (nullptr == writer) { AERROR << "cyber_PyRecordWriter_WriteMessage:writer ptr is null!"; @@ -385,8 +385,8 @@ PyObject *cyber_PyRecordWriter_SetSizeOfFileSegmentation(PyObject *self, Py_RETURN_FALSE; } - auto writer = PyObjectToPtr( - pyobj_rec_writer, "apollo_cybertron_record_pyrecordfilewriter"); + auto writer = PyObjectToPtr( + pyobj_rec_writer, "apollo_cyber_record_pyrecordfilewriter"); if (nullptr == writer) { AERROR @@ -415,8 +415,8 @@ PyObject *cyber_PyRecordWriter_SetIntervalOfFileSegmentation(PyObject *self, Py_RETURN_FALSE; } - auto writer = PyObjectToPtr( - pyobj_rec_writer, "apollo_cybertron_record_pyrecordfilewriter"); + auto writer = PyObjectToPtr( + pyobj_rec_writer, "apollo_cyber_record_pyrecordfilewriter"); if (nullptr == writer) { AERROR << "cyber_PyRecordWriter_SetIntervalOfFileSegmentation:writer ptr " @@ -444,8 +444,8 @@ PyObject *cyber_PyRecordWriter_GetMessageNumber(PyObject *self, } auto writer = - (apollo::cybertron::record::PyRecordWriter *)PyCapsule_GetPointer( - pyobj_rec_writer, "apollo_cybertron_record_pyrecordfilewriter"); + (apollo::cyber::record::PyRecordWriter *)PyCapsule_GetPointer( + pyobj_rec_writer, "apollo_cyber_record_pyrecordfilewriter"); if (nullptr == writer) { AERROR << "PyRecordWriter_GetMessageNumber ptr is null!"; return PyLong_FromUnsignedLongLong(0); @@ -466,8 +466,8 @@ PyObject *cyber_PyRecordWriter_GetMessageType(PyObject *self, PyObject *args) { } auto writer = - (apollo::cybertron::record::PyRecordWriter *)PyCapsule_GetPointer( - pyobj_rec_writer, "apollo_cybertron_record_pyrecordfilewriter"); + (apollo::cyber::record::PyRecordWriter *)PyCapsule_GetPointer( + pyobj_rec_writer, "apollo_cyber_record_pyrecordfilewriter"); if (nullptr == writer) { AERROR << "PyRecordWriter_GetMessageType ptr is null!"; return PYOBJECT_NULL_STRING; @@ -488,8 +488,8 @@ PyObject *cyber_PyRecordWriter_GetProtoDesc(PyObject *self, PyObject *args) { } auto writer = - (apollo::cybertron::record::PyRecordWriter *)PyCapsule_GetPointer( - pyobj_rec_writer, "apollo_cybertron_record_pyrecordfilewriter"); + (apollo::cyber::record::PyRecordWriter *)PyCapsule_GetPointer( + pyobj_rec_writer, "apollo_cyber_record_pyrecordfilewriter"); if (nullptr == writer) { AERROR << "PyRecordWriter_GetProtoDesc ptr is null!"; return PYOBJECT_NULL_STRING; diff --git a/cybertron/py_wrapper/py_init.h b/cyber/py_wrapper/py_init.h similarity index 91% rename from cybertron/py_wrapper/py_init.h rename to cyber/py_wrapper/py_init.h index ac3baba4fa0..f108cc689e8 100644 --- a/cybertron/py_wrapper/py_init.h +++ b/cyber/py_wrapper/py_init.h @@ -19,11 +19,11 @@ #include -#include "cybertron/cybertron.h" -#include "cybertron/init.h" +#include "cyber/cyber.h" +#include "cyber/init.h" namespace apollo { -namespace cybertron { +namespace cyber { bool py_init() { if (!Init("cyber_python")) { @@ -42,7 +42,7 @@ bool py_is_shutdown() { return IsShutdown(); } void py_waitforshutdown() { return WaitForShutdown(); } -} // namespace cybertron +} // namespace cyber } // namespace apollo #endif // PYTHON_WRAPPER_PY_INIT_H_ diff --git a/cybertron/py_wrapper/py_node.h b/cyber/py_wrapper/py_node.h similarity index 70% rename from cybertron/py_wrapper/py_node.h rename to cyber/py_wrapper/py_node.h index d671a35b8c3..2574d07d1f0 100644 --- a/cybertron/py_wrapper/py_node.h +++ b/cyber/py_wrapper/py_node.h @@ -27,42 +27,42 @@ #include #include -#include "cybertron/cybertron.h" -#include "cybertron/init.h" -#include "cybertron/message/protobuf_factory.h" -#include "cybertron/message/py_message.h" -#include "cybertron/message/raw_message.h" -#include "cybertron/node/node.h" -#include "cybertron/node/reader.h" -#include "cybertron/node/writer.h" +#include "cyber/cyber.h" +#include "cyber/init.h" +#include "cyber/message/protobuf_factory.h" +#include "cyber/message/py_message.h" +#include "cyber/message/raw_message.h" +#include "cyber/node/node.h" +#include "cyber/node/reader.h" +#include "cyber/node/writer.h" namespace apollo { -namespace cybertron { +namespace cyber { -bool py_is_shutdown() { return cybertron::IsShutdown(); } +bool py_is_shutdown() { return cyber::IsShutdown(); } bool py_init() { static bool inited = false; if (inited) { - AINFO << "cybertron already inited."; + AINFO << "cyber already inited."; return true; } - if (!apollo::cybertron::Init("cyber_python")) { - AINFO << "cybertron::Init failed."; + if (!apollo::cyber::Init("cyber_python")) { + AINFO << "cyber::Init failed."; return false; } inited = true; - AINFO << "cybertron init succ."; + AINFO << "cyber init succ."; return true; } -bool py_OK() { return apollo::cybertron::OK(); } +bool py_OK() { return apollo::cyber::OK(); } class PyWriter { public: PyWriter(const std::string &channel, const std::string &type, - const uint32_t qos_depth, apollo::cybertron::Node *node) + const uint32_t qos_depth, apollo::cyber::Node *node) : channel_name_(channel), data_type_(type), qos_depth_(qos_depth), @@ -80,7 +80,7 @@ class PyWriter { role_attr.set_proto_desc(proto_desc); auto qos_profile = role_attr.mutable_qos_profile(); qos_profile->set_depth(qos_depth_); - writer_ = node_->CreateWriter( + writer_ = node_->CreateWriter( role_attr); } @@ -88,7 +88,7 @@ class PyWriter { int write(const std::string &data) { auto message = - std::make_shared(data, data_type_); + std::make_shared(data, data_type_); message->set_type_name(data_type_); return writer_->Write(message); } @@ -97,21 +97,21 @@ class PyWriter { std::string channel_name_; std::string data_type_; uint32_t qos_depth_; - apollo::cybertron::Node *node_ = nullptr; + apollo::cyber::Node *node_ = nullptr; std::shared_ptr< - apollo::cybertron::Writer> + apollo::cyber::Writer> writer_; }; class PyReader { public: PyReader(const std::string &channel, const std::string &type, - apollo::cybertron::Node *node) + apollo::cyber::Node *node) : node_(node), channel_name_(channel), data_type_(type), func_(nullptr) { auto f = [this]( - const std::shared_ptr + const std::shared_ptr &request) { this->cb(request); }; - reader_ = node_->CreateReader( + reader_ = node_->CreateReader( channel, f); } @@ -141,7 +141,7 @@ class PyReader { } private: - void cb(const std::shared_ptr + void cb(const std::shared_ptr &message) { { std::lock_guard lg(msg_lock_); @@ -153,12 +153,12 @@ class PyReader { msg_cond_.notify_one(); } - apollo::cybertron::Node *node_; + apollo::cyber::Node *node_; std::string channel_name_; std::string data_type_; int (*func_)(const char *) = nullptr; std::shared_ptr< - apollo::cybertron::Reader> + apollo::cyber::Reader> reader_; std::deque cache_; std::mutex msg_lock_; @@ -168,19 +168,19 @@ class PyReader { class PyService { public: PyService(const std::string &service_name, const std::string &data_type, - apollo::cybertron::Node *node) + apollo::cyber::Node *node) : node_(node), service_name_(service_name), data_type_(data_type), func_(nullptr) { auto f = [this]( - const std::shared_ptr + const std::shared_ptr &request, - std::shared_ptr &response) { + std::shared_ptr &response) { this->cb(request, response); }; - service_ = node_->CreateService( + service_ = node_->CreateService( service_name, f); } @@ -204,9 +204,9 @@ class PyService { private: void cb( - const std::shared_ptr + const std::shared_ptr &request, - std::shared_ptr &response) { // NOLINT + std::shared_ptr &response) { // NOLINT std::lock_guard lg(msg_lock_); request_cache_.push_back(request->data()); @@ -221,18 +221,18 @@ class PyService { response_cache_.pop_front(); } - std::shared_ptr m; - m.reset(new apollo::cybertron::message::PyMessageWrap(msg, data_type_)); + std::shared_ptr m; + m.reset(new apollo::cyber::message::PyMessageWrap(msg, data_type_)); response = m; } - apollo::cybertron::Node *node_; + apollo::cyber::Node *node_; std::string service_name_; std::string data_type_; int (*func_)(const char *) = nullptr; std::shared_ptr< - apollo::cybertron::Service> + apollo::cyber::Service> service_; std::mutex msg_lock_; std::deque request_cache_; @@ -242,18 +242,18 @@ class PyService { class PyClient { public: PyClient(const std::string &name, const std::string &data_type, - apollo::cybertron::Node *node) + apollo::cyber::Node *node) : node_(node), service_name_(name), data_type_(data_type) { client_ = - node_->CreateClient(name); + node_->CreateClient(name); } ~PyClient() {} std::string send_request(std::string request) { - std::shared_ptr m; - m.reset(new apollo::cybertron::message::PyMessageWrap(request, data_type_)); + std::shared_ptr m; + m.reset(new apollo::cyber::message::PyMessageWrap(request, data_type_)); auto response = client_->SendRequest(m); if (response == nullptr) { @@ -266,19 +266,19 @@ class PyClient { } private: - apollo::cybertron::Node *node_; + apollo::cyber::Node *node_; std::string service_name_; std::string data_type_; std::shared_ptr< - apollo::cybertron::Client> + apollo::cyber::Client> client_; }; class PyNode { public: explicit PyNode(const std::string &node_name) : node_name_(node_name) { - node_ = apollo::cybertron::CreateNode(node_name); + node_ = apollo::cyber::CreateNode(node_name); } ~PyNode() {} @@ -297,7 +297,7 @@ class PyNode { } void register_message(const std::string &desc) { - apollo::cybertron::message::ProtobufFactory::Instance() + apollo::cyber::message::ProtobufFactory::Instance() ->RegisterPythonMessage(desc); } @@ -325,10 +325,10 @@ class PyNode { private: std::string node_name_; - std::unique_ptr node_ = nullptr; + std::unique_ptr node_ = nullptr; }; -} // namespace cybertron +} // namespace cyber } // namespace apollo #endif // PYTHON_WRAPPER_PY_NODE_H_ diff --git a/cybertron/py_wrapper/py_record.h b/cyber/py_wrapper/py_record.h similarity index 88% rename from cybertron/py_wrapper/py_record.h rename to cyber/py_wrapper/py_record.h index d6b8ba91d4f..0405597fc6c 100644 --- a/cybertron/py_wrapper/py_record.h +++ b/cyber/py_wrapper/py_record.h @@ -26,22 +26,22 @@ #include #include -#include "cybertron/cybertron.h" -#include "cybertron/init.h" -#include "cybertron/message/protobuf_factory.h" -#include "cybertron/message/py_message.h" -#include "cybertron/message/raw_message.h" -#include "cybertron/proto/record.pb.h" -#include "cybertron/record/record_message.h" -#include "cybertron/record/record_reader.h" -#include "cybertron/record/record_writer.h" - -using ::apollo::cybertron::proto::Header; -using ::apollo::cybertron::record::RecordReader; -using ::apollo::cybertron::record::RecordFileWriter; +#include "cyber/cyber.h" +#include "cyber/init.h" +#include "cyber/message/protobuf_factory.h" +#include "cyber/message/py_message.h" +#include "cyber/message/raw_message.h" +#include "cyber/proto/record.pb.h" +#include "cyber/record/record_message.h" +#include "cyber/record/record_reader.h" +#include "cyber/record/record_writer.h" + +using ::apollo::cyber::proto::Header; +using ::apollo::cyber::record::RecordReader; +using ::apollo::cyber::record::RecordFileWriter; namespace apollo { -namespace cybertron { +namespace cyber { namespace record { struct BagMessage { @@ -152,7 +152,7 @@ class PyRecordWriter { }; } // namespace record -} // namespace cybertron +} // namespace cyber } // namespace apollo #endif // PYTHON_WRAPPER_PY_RECORD_H_ diff --git a/cybertron/py_wrapper/test/test_init.cc b/cyber/py_wrapper/test/test_init.cc similarity index 80% rename from cybertron/py_wrapper/test/test_init.cc rename to cyber/py_wrapper/test/test_init.cc index bcc3dfe9a6a..197d6d88b49 100644 --- a/cybertron/py_wrapper/test/test_init.cc +++ b/cyber/py_wrapper/test/test_init.cc @@ -16,18 +16,18 @@ #include -#include "cybertron/cybertron.h" -#include "cybertron/py_wrapper/py_node.h" +#include "cyber/cyber.h" +#include "cyber/py_wrapper/py_node.h" #include "gtest/gtest.h" TEST(CyberInitTest, test_init) { - EXPECT_TRUE(apollo::cybertron::OK()); - apollo::cybertron::Shutdown(); - EXPECT_TRUE(apollo::cybertron::IsShutdown()); + EXPECT_TRUE(apollo::cyber::OK()); + apollo::cyber::Shutdown(); + EXPECT_TRUE(apollo::cyber::IsShutdown()); } int main(int argc, char** argv) { - apollo::cybertron::Init(argv[0]); + apollo::cyber::Init(argv[0]); testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } diff --git a/cybertron/py_wrapper/test/test_node.cc b/cyber/py_wrapper/test/test_node.cc similarity index 70% rename from cybertron/py_wrapper/test/test_node.cc rename to cyber/py_wrapper/test/test_node.cc index f8313570ff5..1e4d48e3a7e 100644 --- a/cybertron/py_wrapper/test/test_node.cc +++ b/cyber/py_wrapper/test/test_node.cc @@ -17,16 +17,16 @@ #include #include -#include "cybertron/cybertron.h" -#include "cybertron/message/py_message.h" -#include "cybertron/proto/chatter.pb.h" -#include "cybertron/py_wrapper/py_node.h" +#include "cyber/cyber.h" +#include "cyber/message/py_message.h" +#include "cyber/proto/chatter.pb.h" +#include "cyber/py_wrapper/py_node.h" #include "gtest/gtest.h" -using apollo::cybertron::message::PyMessageWrap; -using apollo::cybertron::Time; +using apollo::cyber::message::PyMessageWrap; +using apollo::cyber::Time; -apollo::cybertron::PyReader *pr = NULL; +apollo::cyber::PyReader *pr = NULL; int cbfun(const char *channel_name) { AINFO << "recv->[ " << channel_name << " ]"; @@ -34,11 +34,11 @@ int cbfun(const char *channel_name) { } TEST(CyberNodeTest, create_reader) { - EXPECT_TRUE(apollo::cybertron::OK()); - apollo::cybertron::proto::Chatter chat; - apollo::cybertron::PyNode node("listener"); + EXPECT_TRUE(apollo::cyber::OK()); + apollo::cyber::proto::Chatter chat; + apollo::cyber::PyNode node("listener"); pr = node.create_reader("channel/chatter", chat.GetTypeName()); - EXPECT_EQ("apollo.cybertron.proto.Chatter", chat.GetTypeName()); + EXPECT_EQ("apollo.cyber.proto.Chatter", chat.GetTypeName()); EXPECT_TRUE(pr != nullptr); pr->register_func(cbfun); delete pr; @@ -46,14 +46,14 @@ TEST(CyberNodeTest, create_reader) { } TEST(CyberNodeTest, create_writer) { - EXPECT_TRUE(apollo::cybertron::OK()); - auto msgChat = std::make_shared(); - apollo::cybertron::PyNode node("talker"); - apollo::cybertron::PyWriter *pw = + EXPECT_TRUE(apollo::cyber::OK()); + auto msgChat = std::make_shared(); + apollo::cyber::PyNode node("talker"); + apollo::cyber::PyWriter *pw = node.create_writer("channel/chatter", msgChat->GetTypeName(), 10); EXPECT_TRUE(pw != nullptr); - EXPECT_TRUE(apollo::cybertron::OK()); + EXPECT_TRUE(apollo::cyber::OK()); uint64_t seq = 5; msgChat->set_timestamp(Time::Now().ToNanosecond()); msgChat->set_lidar_timestamp(Time::Now().ToNanosecond()); @@ -69,7 +69,7 @@ TEST(CyberNodeTest, create_writer) { } int main(int argc, char **argv) { - apollo::cybertron::Init(argv[0]); + apollo::cyber::Init(argv[0]); testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } diff --git a/cybertron/py_wrapper/test/test_record.cc b/cyber/py_wrapper/test/test_record.cc similarity index 83% rename from cybertron/py_wrapper/test/test_record.cc rename to cyber/py_wrapper/test/test_record.cc index 33cc36ec5d1..268ab1d92a7 100644 --- a/cybertron/py_wrapper/test/test_record.cc +++ b/cyber/py_wrapper/test/test_record.cc @@ -17,20 +17,20 @@ #include #include -#include "cybertron/cybertron.h" -#include "cybertron/proto/chatter.pb.h" -#include "cybertron/py_wrapper/py_record.h" +#include "cyber/cyber.h" +#include "cyber/proto/chatter.pb.h" +#include "cyber/py_wrapper/py_record.h" #include "gtest/gtest.h" const char TEST_RECORD_FILE[] = "test02.record"; const char CHAN_1[] = "channel/chatter"; const char CHAN_2[] = "/test2"; -const char MSG_TYPE[] = "apollo.cybertron.proto.Test"; +const char MSG_TYPE[] = "apollo.cyber.proto.Test"; const char STR_10B[] = "1234567890"; const char TEST_FILE[] = "test.record"; TEST(CyberRecordTest, record_readerwriter) { - apollo::cybertron::record::PyRecordWriter rec_writer; + apollo::cyber::record::PyRecordWriter rec_writer; EXPECT_TRUE(rec_writer.Open(TEST_RECORD_FILE)); rec_writer.WriteChannel(CHAN_1, MSG_TYPE, STR_10B); @@ -41,12 +41,12 @@ TEST(CyberRecordTest, record_readerwriter) { rec_writer.Close(); // read - apollo::cybertron::record::PyRecordReader rec_reader(TEST_RECORD_FILE); + apollo::cyber::record::PyRecordReader rec_reader(TEST_RECORD_FILE); AINFO << "++++ begin reading"; sleep(1); int count = 0; - apollo::cybertron::record::BagMessage bag_msg = rec_reader.ReadMessage(); + apollo::cyber::record::BagMessage bag_msg = rec_reader.ReadMessage(); std::set channel_list = rec_reader.GetChannelList(); EXPECT_EQ(1, channel_list.size()); @@ -60,7 +60,7 @@ TEST(CyberRecordTest, record_readerwriter) { EXPECT_EQ(MSG_TYPE, bag_msg.data_type); EXPECT_EQ(MSG_TYPE, rec_reader.GetMessageType(channel_name)); std::string header_str = rec_reader.GetHeaderString(); - apollo::cybertron::proto::Header header; + apollo::cyber::proto::Header header; header.ParseFromString(header_str); EXPECT_EQ(1, header.major_version()); EXPECT_EQ(0, header.minor_version()); @@ -70,7 +70,7 @@ TEST(CyberRecordTest, record_readerwriter) { } int main(int argc, char** argv) { - apollo::cybertron::Init(argv[0]); + apollo::cyber::Init(argv[0]); testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } diff --git a/cyber/python/cyber/__init__.py b/cyber/python/cyber/__init__.py new file mode 100644 index 00000000000..8301dea052a --- /dev/null +++ b/cyber/python/cyber/__init__.py @@ -0,0 +1,22 @@ + +# **************************************************************************** +# Copyright 2017 The Apollo Authors. All Rights Reserved. + +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# **************************************************************************** + + +from . import cyber +from . import record + + diff --git a/cyber/python/cyber/cyber.py b/cyber/python/cyber/cyber.py new file mode 100644 index 00000000000..3ef29c5558a --- /dev/null +++ b/cyber/python/cyber/cyber.py @@ -0,0 +1,265 @@ +# **************************************************************************** +# Copyright 2018 The Apollo Authors. All Rights Reserved. + +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# **************************************************************************** +# -*- coding: utf-8 -*- +"""Module for init environment.""" + +import sys +import os +import importlib +import time +import threading +import ctypes + +from google.protobuf.descriptor_pb2 import FileDescriptorProto + +PY_CALLBACK_TYPE = ctypes.CFUNCTYPE(ctypes.c_int, ctypes.c_char_p) +PY_CALLBACK_TYPE_T = ctypes.CFUNCTYPE(ctypes.c_int, ctypes.c_char_p) + +# init vars +CYBER_PATH = os.environ['CYBER_PATH'] +CYBER_DIR = os.path.split(CYBER_PATH)[0] +sys.path.append(CYBER_PATH + "/third_party/") +sys.path.append(CYBER_PATH + "/lib/") +sys.path.append(CYBER_PATH + "/python/cyber") + +sys.path.append(CYBER_DIR + "/python/") +sys.path.append(CYBER_DIR + "/cyber/") + +_CYBER_INIT = importlib.import_module('_cyber_init') +_CYBER_NODE = importlib.import_module('_cyber_node') + + +def init(): + """ + init cyber. + """ + return _CYBER_INIT.py_init() + + +def ok(): + """ + is cyber envi ok. + """ + return _CYBER_INIT.py_ok() + + +def shutdown(): + """ + shutdown cyber envi. + """ + return _CYBER_INIT.py_shutdown() + + +def is_shutdown(): + """ + is cyber shutdown. + """ + return _CYBER_INIT.py_is_shutdown() + + +def waitforshutdown(): + """ + waitforshutdown. + """ + return _CYBER_INIT.py_waitforshutdown() + +# //////////////////////////////class////////////////////////////// + +class Writer(object): + """ + Class for cyber writer wrapper. + """ + + def __init__(self, name, writer, data_type): + self.name = name + self.writer = writer + self.data_type = data_type + + def write(self, data): + """ + writer msg string + """ + return _CYBER_NODE.PyWriter_write(self.writer, data.SerializeToString()) + + +class Reader(object): + """ + Class for cyber reader wrapper. + """ + + def __init__(self, name, reader, data_type): + self.name = name + self.reader = reader + self.data_type = data_type + + +class Client(object): + """ + Class for cyber service client wrapper. + """ + + def __init__(self, client, data_type): + self.client = client + self.data_type = data_type + + def send_request(self, data): + """ + send request to service + @param self + @param data: proto message to send + @return : None or response + """ + response_str = _CYBER_NODE.PyClient_send_request( + self.client, data.SerializeToString()) + if len(response_str) == 0: + return None + + response = self.data_type() + response.ParseFromString(response_str) + return response + + +class Node(object): + """ + Class for cyber Node wrapper. + """ + + def __init__(self, name): + self.node = _CYBER_NODE.new_PyNode(name) + self.list_writer = [] + self.list_reader = [] + self.subs = {} + self.pubs = {} + self.mutex = threading.Lock() + self.callbacks = {} + + def __del__(self): + #print("+++ node __del___") + for writer in self.list_writer: + _CYBER_NODE.delete_PyWriter(writer) + for reader in self.list_reader: + _CYBER_NODE.delete_PyReader(reader) + _CYBER_NODE.delete_PyNode(self.node) + + def register_message(self, file_desc): + """ + register proto message desc file. + """ + for dep in file_desc.dependencies: + self.register_message(dep) + proto = FileDescriptorProto() + file_desc.CopyToProto(proto) + proto.name = file_desc.name + desc_str = proto.SerializeToString() + _CYBER_NODE.PyNode_register_message(self.node, desc_str) + + def create_writer(self, name, data_type, qos_depth=1): + """ + create a topic writer for send message to topic. + @param self + @param name str: topic name + @param data_type proto: message class for serialization + """ + self.register_message(data_type.DESCRIPTOR.file) + datatype = data_type.DESCRIPTOR.full_name + writer = _CYBER_NODE.PyNode_create_writer(self.node, name, + datatype, qos_depth) + self.list_writer.append(writer) + return Writer(name, writer, datatype) + + def reader_callback(self, name): + """ + reader callback + """ + sub = self.subs[name] + msg_str = _CYBER_NODE.PyReader_read(sub[0], False) + if len(msg_str) > 0: + proto = sub[3]() + proto.ParseFromString(msg_str) + # response = None + if sub[2] is None: + sub[1](proto) + else: + sub[1](proto, sub[2]) + return 0 + + def create_reader(self, name, data_type, callback, args=None): + """ + create a topic reader for receive message from topic. + @param self + @param name str: topic name + @param data_type proto: message class for serialization + @callback fn: function to call (fn(data)) when data is + received. If args is set, the function must + accept the args as a second argument, + i.e. fn(data, args) + @args any: additional arguments to pass to the callback + """ + self.mutex.acquire() + if name in self.subs.keys(): + self.mutex.release() + return None + self.mutex.release() + + # datatype = data_type.DESCRIPTOR.full_name + reader = _CYBER_NODE.PyNode_create_reader( + self.node, name, str(data_type)) + if reader is None: + return None + self.list_reader.append(reader) + sub = (reader, callback, args, data_type, False) + + self.mutex.acquire() + self.subs[name] = sub + self.mutex.release() + fun_reader_cb = PY_CALLBACK_TYPE(self.reader_callback) + self.callbacks[name] = fun_reader_cb + f_ptr = ctypes.cast(self.callbacks[name], ctypes.c_void_p).value + _CYBER_NODE.PyReader_register_func(reader, f_ptr) + + return Reader(name, reader, data_type) + + def spin(self): + """ + spin in wait and process message. + @param self + """ + while not _CYBER_NODE.py_is_shutdown(): + time.sleep(0.002) + self.do_executable() + + def do_executable(self): + """ + process received message. + @param self + """ + self.mutex.acquire() + for _, item in self.subs.items(): + msg_str = _CYBER_NODE.PyReader_read(item[0], False) + if len(msg_str) > 0: + if item[4]: + if item[2] is None: + item[1](msg_str) + else: + item[1](msg_str, item[2]) + else: + proto = item[3]() + proto.ParseFromString(msg_str) + if item[2] is None: + item[1](proto) + else: + item[1](proto, item[2]) + self.mutex.release() diff --git a/cyber/python/cyber/record.py b/cyber/python/cyber/record.py new file mode 100644 index 00000000000..588d0342b9b --- /dev/null +++ b/cyber/python/cyber/record.py @@ -0,0 +1,185 @@ +# **************************************************************************** +# Copyright 2018 The Apollo Authors. All Rights Reserved. + +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# **************************************************************************** +# -*- coding: utf-8 -*- +"""Module for wrapper cyber record.""" + +import sys +import os +import importlib +import collections +from google.protobuf.descriptor_pb2 import FileDescriptorProto + +# init vars +CYBER_PATH = os.environ['CYBER_PATH'] +CYBER_DIR = os.path.split(CYBER_PATH)[0] +sys.path.append(CYBER_PATH + "/third_party/") +sys.path.append(CYBER_PATH + "/lib/") +sys.path.append(CYBER_PATH + "/python/cyber") + +sys.path.append(CYBER_DIR + "/python/") +sys.path.append(CYBER_DIR + "/cyber/") + +_CYBER_RECORD = importlib.import_module('_cyber_record') +PyBagMessage = collections.namedtuple('PyBagMessage', + 'topic message data_type timestamp') +#//////////////////////////////record file class////////////////////////////// +class RecordReader(object): + """ + Class for cyber RecordReader wrapper. + """ + def __init__(self, file_name): + self.record_reader = _CYBER_RECORD.new_PyRecordReader(file_name) + + def __del__(self): + _CYBER_RECORD.delete_PyRecordReader(self.record_reader) + + def read_messages(self, start_time=0, end_time=18446744073709551615): + """ + read message from bag file. + @param self + @param start_time: + @param end_time: + @return: generator of (message, data_type, timestamp) + """ + while True: + message = _CYBER_RECORD.PyRecordReader_ReadMessage( + self.record_reader, start_time, end_time) + + if not message["end"]: + yield PyBagMessage(message["channel_name"], message["data"], + message["data_type"], message["timestamp"]) + else: + #print "No message more." + break + + def get_messagenumber(self, channel_name): + """ + return message count. + """ + return _CYBER_RECORD.PyRecordReader_GetMessageNumber( + self.record_reader, channel_name) + + def get_messagetype(self, channel_name): + """ + return message type. + """ + return _CYBER_RECORD.PyRecordReader_GetMessageType( + self.record_reader, channel_name) + + def get_protodesc(self, channel_name): + """ + return message protodesc. + """ + return _CYBER_RECORD.PyRecordReader_GetProtoDesc( + self.record_reader, channel_name) + + def get_headerstring(self): + """ + return message header string. + """ + return _CYBER_RECORD.PyRecordReader_GetHeaderString(self.record_reader) + + def reset(self): + """ + return reset. + """ + return _CYBER_RECORD.PyRecordReader_Reset(self.record_reader) + + def get_channellist(self): + """ + return channel list. + """ + return _CYBER_RECORD.PyRecordReader_GetChannelList(self.record_reader) + +class RecordWriter(object): + """ + Class for cyber RecordWriter wrapper. + """ + def __init__(self): + self.record_writer = _CYBER_RECORD.new_PyRecordWriter() + + def __del__(self): + _CYBER_RECORD.delete_PyRecordWriter(self.record_writer) + + def open(self, path): + """ + open record file for write. + """ + return _CYBER_RECORD.PyRecordWriter_Open(self.record_writer, path) + + def close(self): + """ + close record file. + """ + _CYBER_RECORD.PyRecordWriter_Close(self.record_writer) + + def write_channel(self, channel_name, type_name, proto_desc): + """ + writer channel by channelname,typename,protodesc + """ + return _CYBER_RECORD.PyRecordWriter_WriteChannel(self.record_writer, + channel_name, type_name, proto_desc) + + def write_message(self, channel_name, data, time, raw=True): + """ + writer msg:channelname,rawmsg,writer time + """ + if raw: + return _CYBER_RECORD.PyRecordWriter_WriteMessage(self.record_writer, + channel_name, data, time, "") + else: + file_desc = data.DESCRIPTOR.file + proto = FileDescriptorProto() + file_desc.CopyToProto(proto) + proto.name = file_desc.name + desc_str = proto.SerializeToString() + return _CYBER_RECORD.PyRecordWriter_WriteMessage(self.record_writer, + channel_name, data.SerializeToString(), time, desc_str) + + def set_size_fileseg(self, size_kilobytes): + """ + return filesegment size. + """ + return _CYBER_RECORD.PyRecordWriter_SetSizeOfFileSegmentation( + self.record_writer, size_kilobytes) + + def set_intervaltime_fileseg(self, time_sec): + """ + return file interval time. + """ + return _CYBER_RECORD.PyRecordWriter_SetIntervalOfFileSegmentation( + self.record_writer, time_sec) + + def get_messagenumber(self, channel_name): + """ + return message count. + """ + return _CYBER_RECORD.PyRecordWriter_GetMessageNumber( + self.record_writer, channel_name) + + def get_messagetype(self, channel_name): + """ + return message type. + """ + return _CYBER_RECORD.PyRecordWriter_GetMessageType( + self.record_writer, channel_name) + + def get_protodesc(self, channel_name): + """ + return message protodesc. + """ + return _CYBER_RECORD.PyRecordWriter_GetProtoDesc( + self.record_writer, channel_name) diff --git a/cyber/python/cyber_py/__init__.py b/cyber/python/cyber_py/__init__.py new file mode 100644 index 00000000000..e69de29bb2d diff --git a/cyber/python/cyber_py/cybertron.py b/cyber/python/cyber_py/cybertron.py new file mode 100644 index 00000000000..448c690c47c --- /dev/null +++ b/cyber/python/cyber_py/cybertron.py @@ -0,0 +1,265 @@ +# **************************************************************************** +# Copyright 2018 The Apollo Authors. All Rights Reserved. + +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# **************************************************************************** +# -*- coding: utf-8 -*- +"""Module for init environment.""" + +import sys +import os +import importlib +import time +import threading +import ctypes + +from google.protobuf.descriptor_pb2 import FileDescriptorProto + +PY_CALLBACK_TYPE = ctypes.CFUNCTYPE(ctypes.c_int, ctypes.c_char_p) +PY_CALLBACK_TYPE_T = ctypes.CFUNCTYPE(ctypes.c_int, ctypes.c_char_p) + +# init vars +CYBER_PATH = os.environ['CYBER_PATH'] +CYERTRON_DIR = os.path.split(CYBER_PATH)[0] +sys.path.append(CYBER_PATH + "/third_party/") +sys.path.append(CYBER_PATH + "/lib/") +sys.path.append(CYBER_PATH + "/python/cyber") + +sys.path.append(CYERTRON_DIR + "/python/") +sys.path.append(CYERTRON_DIR + "/cyber/") + +_CYBER_INIT = importlib.import_module('_cyber_init') +_CYBER_NODE = importlib.import_module('_cyber_node') + + +def init(): + """ + init cyber. + """ + return _CYBER_INIT.py_init() + + +def ok(): + """ + is cyber envi ok. + """ + return _CYBER_INIT.py_ok() + + +def shutdown(): + """ + shutdown cyber envi. + """ + return _CYBER_INIT.py_shutdown() + + +def is_shutdown(): + """ + is cyber shutdown. + """ + return _CYBER_INIT.py_is_shutdown() + + +def waitforshutdown(): + """ + waitforshutdown. + """ + return _CYBER_INIT.py_waitforshutdown() + +# //////////////////////////////class////////////////////////////// + +class Writer(object): + """ + Class for cyber writer wrapper. + """ + + def __init__(self, name, writer, data_type): + self.name = name + self.writer = writer + self.data_type = data_type + + def write(self, data): + """ + writer msg string + """ + return _CYBER_NODE.PyWriter_write(self.writer, data.SerializeToString()) + + +class Reader(object): + """ + Class for cyber reader wrapper. + """ + + def __init__(self, name, reader, data_type): + self.name = name + self.reader = reader + self.data_type = data_type + + +class Client(object): + """ + Class for cyber service client wrapper. + """ + + def __init__(self, client, data_type): + self.client = client + self.data_type = data_type + + def send_request(self, data): + """ + send request to service + @param self + @param data: proto message to send + @return : None or response + """ + response_str = _CYBER_NODE.PyClient_send_request( + self.client, data.SerializeToString()) + if len(response_str) == 0: + return None + + response = self.data_type() + response.ParseFromString(response_str) + return response + + +class Node(object): + """ + Class for cyber Node wrapper. + """ + + def __init__(self, name): + self.node = _CYBER_NODE.new_PyNode(name) + self.list_writer = [] + self.list_reader = [] + self.subs = {} + self.pubs = {} + self.mutex = threading.Lock() + self.callbacks = {} + + def __del__(self): + #print("+++ node __del___") + for writer in self.list_writer: + _CYBER_NODE.delete_PyWriter(writer) + for reader in self.list_reader: + _CYBER_NODE.delete_PyReader(reader) + _CYBER_NODE.delete_PyNode(self.node) + + def register_message(self, file_desc): + """ + register proto message desc file. + """ + for dep in file_desc.dependencies: + self.register_message(dep) + proto = FileDescriptorProto() + file_desc.CopyToProto(proto) + proto.name = file_desc.name + desc_str = proto.SerializeToString() + _CYBER_NODE.PyNode_register_message(self.node, desc_str) + + def create_writer(self, name, data_type, qos_depth=1): + """ + create a topic writer for send message to topic. + @param self + @param name str: topic name + @param data_type proto: message class for serialization + """ + self.register_message(data_type.DESCRIPTOR.file) + datatype = data_type.DESCRIPTOR.full_name + writer = _CYBER_NODE.PyNode_create_writer(self.node, name, + datatype, qos_depth) + self.list_writer.append(writer) + return Writer(name, writer, datatype) + + def reader_callback(self, name): + """ + reader callback + """ + sub = self.subs[name] + msg_str = _CYBER_NODE.PyReader_read(sub[0], False) + if len(msg_str) > 0: + proto = sub[3]() + proto.ParseFromString(msg_str) + # response = None + if sub[2] is None: + sub[1](proto) + else: + sub[1](proto, sub[2]) + return 0 + + def create_reader(self, name, data_type, callback, args=None): + """ + create a topic reader for receive message from topic. + @param self + @param name str: topic name + @param data_type proto: message class for serialization + @callback fn: function to call (fn(data)) when data is + received. If args is set, the function must + accept the args as a second argument, + i.e. fn(data, args) + @args any: additional arguments to pass to the callback + """ + self.mutex.acquire() + if name in self.subs.keys(): + self.mutex.release() + return None + self.mutex.release() + + # datatype = data_type.DESCRIPTOR.full_name + reader = _CYBER_NODE.PyNode_create_reader( + self.node, name, str(data_type)) + if reader is None: + return None + self.list_reader.append(reader) + sub = (reader, callback, args, data_type, False) + + self.mutex.acquire() + self.subs[name] = sub + self.mutex.release() + fun_reader_cb = PY_CALLBACK_TYPE(self.reader_callback) + self.callbacks[name] = fun_reader_cb + f_ptr = ctypes.cast(self.callbacks[name], ctypes.c_void_p).value + _CYBER_NODE.PyReader_register_func(reader, f_ptr) + + return Reader(name, reader, data_type) + + def spin(self): + """ + spin in wait and process message. + @param self + """ + while not _CYBER_NODE.py_is_shutdown(): + time.sleep(0.002) + self.do_executable() + + def do_executable(self): + """ + process received message. + @param self + """ + self.mutex.acquire() + for _, item in self.subs.items(): + msg_str = _CYBER_NODE.PyReader_read(item[0], False) + if len(msg_str) > 0: + if item[4]: + if item[2] is None: + item[1](msg_str) + else: + item[1](msg_str, item[2]) + else: + proto = item[3]() + proto.ParseFromString(msg_str) + if item[2] is None: + item[1](proto) + else: + item[1](proto, item[2]) + self.mutex.release() diff --git a/cyber/python/cyber_py/record.py b/cyber/python/cyber_py/record.py new file mode 100644 index 00000000000..609964e2c54 --- /dev/null +++ b/cyber/python/cyber_py/record.py @@ -0,0 +1,185 @@ +# **************************************************************************** +# Copyright 2018 The Apollo Authors. All Rights Reserved. + +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# **************************************************************************** +# -*- coding: utf-8 -*- +"""Module for wrapper cyber record.""" + +import sys +import os +import importlib +import collections +from google.protobuf.descriptor_pb2 import FileDescriptorProto + +# init vars +CYBER_PATH = os.environ['CYBER_PATH'] +CYERTRON_DIR = os.path.split(CYBER_PATH)[0] +sys.path.append(CYBER_PATH + "/third_party/") +sys.path.append(CYBER_PATH + "/lib/") +sys.path.append(CYBER_PATH + "/python/cyber") + +sys.path.append(CYERTRON_DIR + "/python/") +sys.path.append(CYERTRON_DIR + "/cyber/") + +_CYBER_RECORD = importlib.import_module('_cyber_record') +PyBagMessage = collections.namedtuple('PyBagMessage', + 'topic message data_type timestamp') +#//////////////////////////////record file class////////////////////////////// +class RecordReader(object): + """ + Class for cyber RecordReader wrapper. + """ + def __init__(self, file_name): + self.record_reader = _CYBER_RECORD.new_PyRecordReader(file_name) + + def __del__(self): + _CYBER_RECORD.delete_PyRecordReader(self.record_reader) + + def read_messages(self, start_time=0, end_time=18446744073709551615): + """ + read message from bag file. + @param self + @param start_time: + @param end_time: + @return: generator of (message, data_type, timestamp) + """ + while True: + message = _CYBER_RECORD.PyRecordReader_ReadMessage( + self.record_reader, start_time, end_time) + + if not message["end"]: + yield PyBagMessage(message["channel_name"], message["data"], + message["data_type"], message["timestamp"]) + else: + #print "No message more." + break + + def get_messagenumber(self, channel_name): + """ + return message count. + """ + return _CYBER_RECORD.PyRecordReader_GetMessageNumber( + self.record_reader, channel_name) + + def get_messagetype(self, channel_name): + """ + return message type. + """ + return _CYBER_RECORD.PyRecordReader_GetMessageType( + self.record_reader, channel_name) + + def get_protodesc(self, channel_name): + """ + return message protodesc. + """ + return _CYBER_RECORD.PyRecordReader_GetProtoDesc( + self.record_reader, channel_name) + + def get_headerstring(self): + """ + return message header string. + """ + return _CYBER_RECORD.PyRecordReader_GetHeaderString(self.record_reader) + + def reset(self): + """ + return reset. + """ + return _CYBER_RECORD.PyRecordReader_Reset(self.record_reader) + + def get_channellist(self): + """ + return channel list. + """ + return _CYBER_RECORD.PyRecordReader_GetChannelList(self.record_reader) + +class RecordWriter(object): + """ + Class for cyber RecordWriter wrapper. + """ + def __init__(self): + self.record_writer = _CYBER_RECORD.new_PyRecordWriter() + + def __del__(self): + _CYBER_RECORD.delete_PyRecordWriter(self.record_writer) + + def open(self, path): + """ + open record file for write. + """ + return _CYBER_RECORD.PyRecordWriter_Open(self.record_writer, path) + + def close(self): + """ + close record file. + """ + _CYBER_RECORD.PyRecordWriter_Close(self.record_writer) + + def write_channel(self, channel_name, type_name, proto_desc): + """ + writer channel by channelname,typename,protodesc + """ + return _CYBER_RECORD.PyRecordWriter_WriteChannel(self.record_writer, + channel_name, type_name, proto_desc) + + def write_message(self, channel_name, data, time, raw=True): + """ + writer msg:channelname,rawmsg,writer time + """ + if raw: + return _CYBER_RECORD.PyRecordWriter_WriteMessage(self.record_writer, + channel_name, data, time, "") + else: + file_desc = data.DESCRIPTOR.file + proto = FileDescriptorProto() + file_desc.CopyToProto(proto) + proto.name = file_desc.name + desc_str = proto.SerializeToString() + return _CYBER_RECORD.PyRecordWriter_WriteMessage(self.record_writer, + channel_name, data.SerializeToString(), time, desc_str) + + def set_size_fileseg(self, size_kilobytes): + """ + return filesegment size. + """ + return _CYBER_RECORD.PyRecordWriter_SetSizeOfFileSegmentation( + self.record_writer, size_kilobytes) + + def set_intervaltime_fileseg(self, time_sec): + """ + return file interval time. + """ + return _CYBER_RECORD.PyRecordWriter_SetIntervalOfFileSegmentation( + self.record_writer, time_sec) + + def get_messagenumber(self, channel_name): + """ + return message count. + """ + return _CYBER_RECORD.PyRecordWriter_GetMessageNumber( + self.record_writer, channel_name) + + def get_messagetype(self, channel_name): + """ + return message type. + """ + return _CYBER_RECORD.PyRecordWriter_GetMessageType( + self.record_writer, channel_name) + + def get_protodesc(self, channel_name): + """ + return message protodesc. + """ + return _CYBER_RECORD.PyRecordWriter_GetProtoDesc( + self.record_writer, channel_name) diff --git a/cybertron/python/examples/cyber_header_pb2.py b/cyber/python/examples/cyber_header_pb2.py similarity index 76% rename from cybertron/python/examples/cyber_header_pb2.py rename to cyber/python/examples/cyber_header_pb2.py index 2f072b4f90f..79628394d03 100644 --- a/cybertron/python/examples/cyber_header_pb2.py +++ b/cyber/python/examples/cyber_header_pb2.py @@ -17,8 +17,8 @@ DESCRIPTOR = _descriptor.FileDescriptor( name='cyber_header.proto', - package='cybertron.proto', - serialized_pb=_b('\n\x12\x63yber_header.proto\x12\x0f\x63ybertron.proto\"Q\n\x0b\x43yberHeader\x12\x12\n\nmeta_stamp\x18\x01 \x01(\x04\x12\r\n\x05stamp\x18\x02 \x01(\x04\x12\r\n\x05index\x18\x03 \x01(\x04\x12\x10\n\x08\x66rame_id\x18\x04 \x01(\t') + package='cyber.proto', + serialized_pb=_b('\n\x12\x63yber_header.proto\x12\x0f\x63yber.proto\"Q\n\x0b\x43yberHeader\x12\x12\n\nmeta_stamp\x18\x01 \x01(\x04\x12\r\n\x05stamp\x18\x02 \x01(\x04\x12\r\n\x05index\x18\x03 \x01(\x04\x12\x10\n\x08\x66rame_id\x18\x04 \x01(\t') ) _sym_db.RegisterFileDescriptor(DESCRIPTOR) @@ -27,34 +27,34 @@ _CYBERHEADER = _descriptor.Descriptor( name='CyberHeader', - full_name='cybertron.proto.CyberHeader', + full_name='cyber.proto.CyberHeader', filename=None, file=DESCRIPTOR, containing_type=None, fields=[ _descriptor.FieldDescriptor( - name='meta_stamp', full_name='cybertron.proto.CyberHeader.meta_stamp', index=0, + name='meta_stamp', full_name='cyber.proto.CyberHeader.meta_stamp', index=0, number=1, type=4, cpp_type=4, label=1, has_default_value=False, default_value=0, message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, options=None), _descriptor.FieldDescriptor( - name='stamp', full_name='cybertron.proto.CyberHeader.stamp', index=1, + name='stamp', full_name='cyber.proto.CyberHeader.stamp', index=1, number=2, type=4, cpp_type=4, label=1, has_default_value=False, default_value=0, message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, options=None), _descriptor.FieldDescriptor( - name='index', full_name='cybertron.proto.CyberHeader.index', index=2, + name='index', full_name='cyber.proto.CyberHeader.index', index=2, number=3, type=4, cpp_type=4, label=1, has_default_value=False, default_value=0, message_type=None, enum_type=None, containing_type=None, is_extension=False, extension_scope=None, options=None), _descriptor.FieldDescriptor( - name='frame_id', full_name='cybertron.proto.CyberHeader.frame_id', index=3, + name='frame_id', full_name='cyber.proto.CyberHeader.frame_id', index=3, number=4, type=9, cpp_type=9, label=1, has_default_value=False, default_value=_b("").decode('utf-8'), message_type=None, enum_type=None, containing_type=None, @@ -80,7 +80,7 @@ CyberHeader = _reflection.GeneratedProtocolMessageType('CyberHeader', (_message.Message,), dict( DESCRIPTOR = _CYBERHEADER, __module__ = 'cyber_header_pb2' - # @@protoc_insertion_point(class_scope:cybertron.proto.CyberHeader) + # @@protoc_insertion_point(class_scope:cyber.proto.CyberHeader) )) _sym_db.RegisterMessage(CyberHeader) diff --git a/cybertron/python/examples/listener.py b/cyber/python/examples/listener.py similarity index 91% rename from cybertron/python/examples/listener.py rename to cyber/python/examples/listener.py index a62e6647112..bee73473ac0 100644 --- a/cybertron/python/examples/listener.py +++ b/cyber/python/examples/listener.py @@ -19,7 +19,7 @@ import sys sys.path.append("../") -from cyber_py import cybertron +from cyber_py import cyber from modules.common.util.testdata.simple_pb2 import SimpleMessage def callback(data): @@ -36,12 +36,12 @@ def test_listener_class(): reader message. """ print "=" * 120 - test_node = cybertron.Node("listener") + test_node = cyber.Node("listener") test_node.create_reader("channel/chatter", SimpleMessage, callback) test_node.spin() if __name__ == '__main__': - cybertron.init() + cyber.init() test_listener_class() - cybertron.shutdown() + cyber.shutdown() diff --git a/cybertron/python/examples/py_listener.cc b/cyber/python/examples/py_listener.cc similarity index 76% rename from cybertron/python/examples/py_listener.cc rename to cyber/python/examples/py_listener.cc index 986ce68e665..fa9856de060 100644 --- a/cybertron/python/examples/py_listener.cc +++ b/cyber/python/examples/py_listener.cc @@ -14,11 +14,11 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/cybertron.h" -#include "cybertron/proto/chatter.pb.h" -#include "cybertron/py_wrapper/py_node.h" +#include "cyber/cyber.h" +#include "cyber/proto/chatter.pb.h" +#include "cyber/py_wrapper/py_node.h" -apollo::cybertron::PyReader *pr = NULL; +apollo::cyber::PyReader *pr = NULL; int cbfun(const char *channel_name) { AINFO << "recv->[ " << channel_name << " ]"; @@ -26,13 +26,13 @@ int cbfun(const char *channel_name) { } int main(int argc, char *argv[]) { - apollo::cybertron::Init("cyber_python"); - apollo::cybertron::proto::Chatter chat; - apollo::cybertron::PyNode node("listener"); + apollo::cyber::Init("cyber_python"); + apollo::cyber::proto::Chatter chat; + apollo::cyber::PyNode node("listener"); pr = node.create_reader("channel/chatter", chat.GetTypeName()); pr->register_func(cbfun); - apollo::cybertron::WaitForShutdown(); + apollo::cyber::WaitForShutdown(); delete pr; return 0; diff --git a/cybertron/python/examples/py_record.cc b/cyber/python/examples/py_record.cc similarity index 83% rename from cybertron/python/examples/py_record.cc rename to cyber/python/examples/py_record.cc index af8875f4d65..190f08c5383 100644 --- a/cybertron/python/examples/py_record.cc +++ b/cyber/python/examples/py_record.cc @@ -16,19 +16,19 @@ #include -#include "cybertron/cybertron.h" -#include "cybertron/proto/chatter.pb.h" -#include "cybertron/py_wrapper/py_record.h" +#include "cyber/cyber.h" +#include "cyber/proto/chatter.pb.h" +#include "cyber/py_wrapper/py_record.h" const char TEST_RECORD_FILE[] = "test02.record"; const char CHAN_1[] = "channel/chatter"; const char CHAN_2[] = "/test2"; -const char MSG_TYPE[] = "apollo.cybertron.proto.Test"; +const char MSG_TYPE[] = "apollo.cyber.proto.Test"; const char STR_10B[] = "1234567890"; const char TEST_FILE[] = "test.record"; void test_write(const std::string &writefile) { - apollo::cybertron::record::PyRecordWriter rec_writer; + apollo::cyber::record::PyRecordWriter rec_writer; AINFO << "++++ begin writer"; rec_writer.Open(writefile); rec_writer.WriteChannel(CHAN_1, MSG_TYPE, STR_10B); @@ -37,12 +37,12 @@ void test_write(const std::string &writefile) { } void test_read(const std::string &readfile) { - apollo::cybertron::record::PyRecordReader rec_reader(readfile); + apollo::cyber::record::PyRecordReader rec_reader(readfile); AINFO << "++++ begin reading"; sleep(1); int count = 0; - apollo::cybertron::record::BagMessage bag_msg = rec_reader.ReadMessage(); + apollo::cyber::record::BagMessage bag_msg = rec_reader.ReadMessage(); while (!bag_msg.end) { AINFO << "========================"; std::string channel_name = bag_msg.channel_name; @@ -60,7 +60,7 @@ void test_read(const std::string &readfile) { AINFO << "reader msg count = " << count; } int main(int argc, char *argv[]) { - apollo::cybertron::Init("cyber_python"); + apollo::cyber::Init("cyber_python"); test_write(TEST_RECORD_FILE); sleep(1); test_read(TEST_RECORD_FILE); diff --git a/cybertron/python/examples/py_talker.cc b/cyber/python/examples/py_talker.cc similarity index 70% rename from cybertron/python/examples/py_talker.cc rename to cyber/python/examples/py_talker.cc index bb47dc41824..1fec388da42 100644 --- a/cybertron/python/examples/py_talker.cc +++ b/cyber/python/examples/py_talker.cc @@ -17,27 +17,27 @@ #include #include -#include "cybertron/cybertron.h" -#include "cybertron/proto/chatter.pb.h" -#include "cybertron/py_wrapper/py_node.h" -#include "cybertron/time/rate.h" -#include "cybertron/time/time.h" +#include "cyber/cyber.h" +#include "cyber/proto/chatter.pb.h" +#include "cyber/py_wrapper/py_node.h" +#include "cyber/time/rate.h" +#include "cyber/time/time.h" -using apollo::cybertron::Rate; -using apollo::cybertron::Time; -using apollo::cybertron::proto::Chatter; +using apollo::cyber::Rate; +using apollo::cyber::Time; +using apollo::cyber::proto::Chatter; -using apollo::cybertron::message::PyMessageWrap; +using apollo::cyber::message::PyMessageWrap; int main(int argc, char *argv[]) { - // init cybertron framework - apollo::cybertron::Init("cyber_python"); - auto msgChat = std::make_shared(); - apollo::cybertron::PyNode node("talker"); - apollo::cybertron::PyWriter *pw = + // init cyber framework + apollo::cyber::Init("cyber_python"); + auto msgChat = std::make_shared(); + apollo::cyber::PyNode node("talker"); + apollo::cyber::PyWriter *pw = node.create_writer("channel/chatter", msgChat->GetTypeName()); Rate rate(1.0); - while (apollo::cybertron::OK()) { + while (apollo::cyber::OK()) { static uint64_t seq = 0; msgChat->set_timestamp(Time::Now().ToNanosecond()); msgChat->set_lidar_timestamp(Time::Now().ToNanosecond()); diff --git a/cybertron/python/examples/record.py b/cyber/python/examples/record.py similarity index 97% rename from cybertron/python/examples/record.py rename to cyber/python/examples/record.py index a737bc829c7..b2e53011d08 100644 --- a/cybertron/python/examples/record.py +++ b/cyber/python/examples/record.py @@ -20,7 +20,7 @@ import sys sys.path.append("../") -from cyber_py import cybertron +from cyber_py import cyber from cyber_py import record from google.protobuf.descriptor_pb2 import FileDescriptorProto from modules.common.util.testdata.simple_pb2 import SimpleMessage @@ -80,7 +80,7 @@ def test_record_reader(reader_path): count = count + 1 if __name__ == '__main__': - cybertron.init() + cyber.init() test_record_writer(TEST_RECORD_FILE) test_record_reader(TEST_RECORD_FILE) - cybertron.shutdown() + cyber.shutdown() diff --git a/cybertron/python/examples/record_trans.py b/cyber/python/examples/record_trans.py similarity index 95% rename from cybertron/python/examples/record_trans.py rename to cyber/python/examples/record_trans.py index ec268168993..ee8d1812fd0 100644 --- a/cybertron/python/examples/record_trans.py +++ b/cyber/python/examples/record_trans.py @@ -19,7 +19,7 @@ import sys sys.path.append("../") -from cyber_py import cybertron +from cyber_py import cyber from cyber_py import record TEST_RECORD_FILE = "trans_ret.record" @@ -50,7 +50,7 @@ def test_record_trans(reader_path): print channel_list if __name__ == '__main__': - cybertron.init() + cyber.init() test_record_trans(sys.argv[1]) - cybertron.shutdown() + cyber.shutdown() diff --git a/cybertron/python/examples/talker.py b/cyber/python/examples/talker.py similarity index 89% rename from cybertron/python/examples/talker.py rename to cyber/python/examples/talker.py index b1f0adf7fd1..7abe85daf5c 100644 --- a/cybertron/python/examples/talker.py +++ b/cyber/python/examples/talker.py @@ -15,7 +15,7 @@ # **************************************************************************** # -*- coding: utf-8 -*- from modules.common.util.testdata.simple_pb2 import SimpleMessage -from cyber_py import cybertron +from cyber_py import cyber """Module for example of talker.""" import time @@ -23,7 +23,6 @@ sys.path.append("../") - def test_talker_class(): """ test talker. @@ -32,12 +31,12 @@ def test_talker_class(): msg.text = "talker:send Alex!" msg.integer = 0 - test_node = cybertron.Node("node_name1") + test_node = cyber.Node("node_name1") g_count = 1 writer = test_node.create_writer("channel/chatter", SimpleMessage, 6) - while not cybertron.is_shutdown(): + while not cyber.is_shutdown(): time.sleep(1) g_count = g_count + 1 msg.integer = g_count @@ -47,6 +46,6 @@ def test_talker_class(): if __name__ == '__main__': - cybertron.init() + cyber.init() test_talker_class() - cybertron.shutdown() + cyber.shutdown() diff --git a/cybertron/python/test/test_init.py b/cyber/python/test/test_init.py similarity index 82% rename from cybertron/python/test/test_init.py rename to cyber/python/test/test_init.py index 1240aa868ee..e5aeb552f45 100644 --- a/cybertron/python/test/test_init.py +++ b/cyber/python/test/test_init.py @@ -20,7 +20,7 @@ import unittest sys.path.append("../") -from cyber_py import cybertron +from cyber_py import cyber class TestInit(unittest.TestCase): """ @@ -28,12 +28,12 @@ class TestInit(unittest.TestCase): """ def test_init(self): """ - test cybertron. + test cyber. """ - self.assertTrue(cybertron.init()) - self.assertTrue(cybertron.ok()) - cybertron.shutdown() - self.assertTrue(cybertron.is_shutdown()) + self.assertTrue(cyber.init()) + self.assertTrue(cyber.ok()) + cyber.shutdown() + self.assertTrue(cyber.is_shutdown()) if __name__ == '__main__': unittest.main() diff --git a/cybertron/python/test/test_node.py b/cyber/python/test/test_node.py similarity index 89% rename from cybertron/python/test/test_node.py rename to cyber/python/test/test_node.py index 52016a9c649..474ee720290 100644 --- a/cybertron/python/test/test_node.py +++ b/cyber/python/test/test_node.py @@ -20,7 +20,7 @@ import unittest sys.path.append("../") -from cyber_py import cybertron +from cyber_py import cyber from modules.common.util.testdata.simple_pb2 import SimpleMessage def callback(data): @@ -38,11 +38,11 @@ class TestNode(unittest.TestCase): """ @classmethod def setUpClass(cls): - cybertron.init() + cyber.init() @classmethod def tearDownClass(cls): - cybertron.shutdown() + cyber.shutdown() def test_writer(self): """ @@ -52,8 +52,8 @@ def test_writer(self): msg.text = "talker:send Alex!" msg.integer = 0 - self.assertTrue(cybertron.ok()) - test_node = cybertron.Node("node_name1") + self.assertTrue(cyber.ok()) + test_node = cyber.Node("node_name1") writer = test_node.create_writer("channel/chatter", SimpleMessage, 7) self.assertEqual(writer.name, "channel/chatter") self.assertEqual(writer.data_type, "apollo.common.util.test.SimpleMessage") @@ -63,8 +63,8 @@ def test_reader(self): """ unit test of reader. """ - self.assertTrue(cybertron.ok()) - test_node = cybertron.Node("listener") + self.assertTrue(cyber.ok()) + test_node = cyber.Node("listener") reader = test_node.create_reader("channel/chatter", SimpleMessage, callback) self.assertEqual(reader.name, "channel/chatter") diff --git a/cybertron/python/test/test_record.py b/cyber/python/test/test_record.py similarity index 96% rename from cybertron/python/test/test_record.py rename to cyber/python/test/test_record.py index bba18baaa4c..5942078c07d 100644 --- a/cybertron/python/test/test_record.py +++ b/cyber/python/test/test_record.py @@ -20,7 +20,7 @@ import unittest sys.path.append("../") -from cyber_py import cybertron +from cyber_py import cyber from cyber_py import record from modules.common.util.testdata.simple_pb2 import SimpleMessage @@ -40,7 +40,7 @@ def test_record_writer_read(self): """ unit test of record. """ - self.assertTrue(cybertron.init()) + self.assertTrue(cyber.init()) # writer fwriter = record.RecordWriter() @@ -81,7 +81,7 @@ def test_record_writer_read(self): self.assertEqual(1, msg.channel_number) self.assertTrue(msg.is_complete) - cybertron.shutdown() + cyber.shutdown() if __name__ == '__main__': unittest.main() diff --git a/cybertron/record/BUILD b/cyber/record/BUILD similarity index 82% rename from cybertron/record/BUILD rename to cyber/record/BUILD index e9e441bb73a..479496d98f2 100644 --- a/cybertron/record/BUILD +++ b/cyber/record/BUILD @@ -20,7 +20,7 @@ cc_library( srcs = [ "header_builder.cc", ], hdrs = [ "header_builder.h", ], deps = [ - "//cybertron/proto:record_cc_proto", + "//cyber/proto:record_cc_proto", ], ) @@ -28,7 +28,7 @@ cc_library( name = "record_base", hdrs = [ "record_base.h", ], deps = [ - "//cybertron/proto:record_cc_proto", + "//cyber/proto:record_cc_proto", ], ) @@ -37,9 +37,9 @@ cc_library( hdrs = [ "record_file.h", ], srcs = [ "record_file.cc", ], deps = [ - "//cybertron/common:file", - "//cybertron/common:log", - "//cybertron/proto:record_cc_proto", + "//cyber/common:file", + "//cyber/common:log", + "//cyber/proto:record_cc_proto", ], ) @@ -77,8 +77,8 @@ cc_library( "header_builder", "record_base", "record_file", - "//cybertron/message:raw_message", - "//cybertron/proto:record_cc_proto", + "//cyber/message:raw_message", + "//cyber/proto:record_cc_proto", ], ) diff --git a/cybertron/record/header_builder.cc b/cyber/record/header_builder.cc similarity index 95% rename from cybertron/record/header_builder.cc rename to cyber/record/header_builder.cc index 832f5efbc0f..25743c1402a 100644 --- a/cybertron/record/header_builder.cc +++ b/cyber/record/header_builder.cc @@ -14,13 +14,13 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/record/header_builder.h" +#include "cyber/record/header_builder.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace record { -using ::apollo::cybertron::proto::CompressType; +using ::apollo::cyber::proto::CompressType; proto::Header HeaderBuilder::GetHeader() { proto::Header header; @@ -85,5 +85,5 @@ proto::Header HeaderBuilder::GetHeaderWithChunkParams( } } // namespace record -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/record/header_builder.h b/cyber/record/header_builder.h similarity index 88% rename from cybertron/record/header_builder.h rename to cyber/record/header_builder.h index 593fd405be9..a40088444f6 100644 --- a/cybertron/record/header_builder.h +++ b/cyber/record/header_builder.h @@ -14,13 +14,13 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_RECORD_HEADER_BUILDER_H_ -#define CYBERTRON_RECORD_HEADER_BUILDER_H_ +#ifndef CYBER_RECORD_HEADER_BUILDER_H_ +#define CYBER_RECORD_HEADER_BUILDER_H_ -#include "cybertron/proto/record.pb.h" +#include "cyber/proto/record.pb.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace record { class HeaderBuilder { @@ -43,7 +43,7 @@ class HeaderBuilder { }; } // namespace record -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_RECORD_HEADER_BUILDER_H_ +#endif // CYBER_RECORD_HEADER_BUILDER_H_ diff --git a/cybertron/record/record_base.h b/cyber/record/record_base.h similarity index 87% rename from cybertron/record/record_base.h rename to cyber/record/record_base.h index 481faae9e3e..deba87f9ea9 100644 --- a/cybertron/record/record_base.h +++ b/cyber/record/record_base.h @@ -14,16 +14,16 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_RECORD_RECORD_BASE_H_ -#define CYBERTRON_RECORD_RECORD_BASE_H_ +#ifndef CYBER_RECORD_RECORD_BASE_H_ +#define CYBER_RECORD_RECORD_BASE_H_ #include #include -#include "cybertron/proto/record.pb.h" +#include "cyber/proto/record.pb.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace record { class RecordBase { @@ -49,7 +49,7 @@ class RecordBase { }; } // namespace record -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_RECORD_RECORD_BASE_H_ +#endif // CYBER_RECORD_RECORD_BASE_H_ diff --git a/cybertron/record/record_file.cc b/cyber/record/record_file.cc similarity index 98% rename from cybertron/record/record_file.cc rename to cyber/record/record_file.cc index c5cfcb16500..20cc310ca60 100644 --- a/cybertron/record/record_file.cc +++ b/cyber/record/record_file.cc @@ -14,10 +14,10 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/record/record_file.h" +#include "cyber/record/record_file.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace record { RecordFile::RecordFile() {} @@ -35,7 +35,7 @@ RecordFileReader::~RecordFileReader() {} bool RecordFileReader::Open(const std::string& path) { std::lock_guard lock(mutex_); path_ = path; - if (!::apollo::cybertron::common::PathExists(path_)) { + if (!::apollo::cyber::common::PathExists(path_)) { AERROR << "file not exist, file: " << path_; return false; } @@ -393,5 +393,5 @@ void RecordFileWriter::Flush() { } } // namespace record -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/record/record_file.h b/cyber/record/record_file.h similarity index 87% rename from cybertron/record/record_file.h rename to cyber/record/record_file.h index 20a87c9cf1f..02ee562d767 100644 --- a/cybertron/record/record_file.h +++ b/cyber/record/record_file.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_RECORD_RECORD_FILE_H_ -#define CYBERTRON_RECORD_RECORD_FILE_H_ +#ifndef CYBER_RECORD_RECORD_FILE_H_ +#define CYBER_RECORD_RECORD_FILE_H_ #include #include @@ -26,28 +26,28 @@ #include #include -#include "cybertron/common/file.h" -#include "cybertron/common/log.h" -#include "cybertron/proto/record.pb.h" +#include "cyber/common/file.h" +#include "cyber/common/log.h" +#include "cyber/proto/record.pb.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace record { const int HEADER_LENGTH = 2048; -using ::apollo::cybertron::proto::Header; -using ::apollo::cybertron::proto::Channel; -using ::apollo::cybertron::proto::ChunkHeader; -using ::apollo::cybertron::proto::ChunkBody; -using ::apollo::cybertron::proto::SingleMessage; -using ::apollo::cybertron::proto::Index; -using ::apollo::cybertron::proto::SingleIndex; -using ::apollo::cybertron::proto::ChannelCache; -using ::apollo::cybertron::proto::ChunkHeaderCache; -using ::apollo::cybertron::proto::ChunkBodyCache; -using ::apollo::cybertron::proto::SectionType; -using ::apollo::cybertron::proto::CompressType; +using ::apollo::cyber::proto::Header; +using ::apollo::cyber::proto::Channel; +using ::apollo::cyber::proto::ChunkHeader; +using ::apollo::cyber::proto::ChunkBody; +using ::apollo::cyber::proto::SingleMessage; +using ::apollo::cyber::proto::Index; +using ::apollo::cyber::proto::SingleIndex; +using ::apollo::cyber::proto::ChannelCache; +using ::apollo::cyber::proto::ChunkHeaderCache; +using ::apollo::cyber::proto::ChunkBodyCache; +using ::apollo::cyber::proto::SectionType; +using ::apollo::cyber::proto::CompressType; struct Section { SectionType type; @@ -226,7 +226,7 @@ bool RecordFileWriter::WriteSection(SectionType type, const T& message, } } // namespace record -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_RECORD_RECORD_FILE_H_ +#endif // CYBER_RECORD_RECORD_FILE_H_ diff --git a/cybertron/record/record_message.h b/cyber/record/record_message.h similarity index 86% rename from cybertron/record/record_message.h rename to cyber/record/record_message.h index f0ed351e6c2..bc977bc5065 100644 --- a/cybertron/record/record_message.h +++ b/cyber/record/record_message.h @@ -14,14 +14,14 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_RECORD_RECORD_MESSAGE_H_ -#define CYBERTRON_RECORD_RECORD_MESSAGE_H_ +#ifndef CYBER_RECORD_RECORD_MESSAGE_H_ +#define CYBER_RECORD_RECORD_MESSAGE_H_ #include #include namespace apollo { -namespace cybertron { +namespace cyber { namespace record { struct RecordMessage { @@ -35,7 +35,7 @@ struct RecordMessage { }; } // namespace record -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_RECORD_RECORD_READER_H_ +#endif // CYBER_RECORD_RECORD_READER_H_ diff --git a/cybertron/record/record_reader.cc b/cyber/record/record_reader.cc similarity index 98% rename from cybertron/record/record_reader.cc rename to cyber/record/record_reader.cc index b36fedc78a7..c0af9d505e4 100644 --- a/cybertron/record/record_reader.cc +++ b/cyber/record/record_reader.cc @@ -14,12 +14,12 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/record/record_reader.h" +#include "cyber/record/record_reader.h" #include namespace apollo { -namespace cybertron { +namespace cyber { namespace record { using proto::SectionType; @@ -169,5 +169,5 @@ const std::string& RecordReader::GetProtoDesc( } } // namespace record -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/record/record_reader.h b/cyber/record/record_reader.h similarity index 85% rename from cybertron/record/record_reader.h rename to cyber/record/record_reader.h index 11d25c0bc27..92188fe8b33 100644 --- a/cybertron/record/record_reader.h +++ b/cyber/record/record_reader.h @@ -14,21 +14,21 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_RECORD_RECORD_READER_H_ -#define CYBERTRON_RECORD_RECORD_READER_H_ +#ifndef CYBER_RECORD_RECORD_READER_H_ +#define CYBER_RECORD_RECORD_READER_H_ #include #include #include #include -#include "cybertron/proto/record.pb.h" -#include "cybertron/record/record_base.h" -#include "cybertron/record/record_file.h" -#include "cybertron/record/record_message.h" +#include "cyber/proto/record.pb.h" +#include "cyber/record/record_base.h" +#include "cyber/record/record_file.h" +#include "cyber/record/record_message.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace record { class RecordReader : public RecordBase { @@ -67,7 +67,7 @@ class RecordReader : public RecordBase { }; } // namespace record -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_RECORD_RECORD_READER_H_ +#endif // CYBER_RECORD_RECORD_READER_H_ diff --git a/cybertron/record/record_viewer.cc b/cyber/record/record_viewer.cc similarity index 96% rename from cybertron/record/record_viewer.cc rename to cyber/record/record_viewer.cc index 60cc5e15545..070206f04c1 100644 --- a/cybertron/record/record_viewer.cc +++ b/cyber/record/record_viewer.cc @@ -14,14 +14,14 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/record/record_viewer.h" +#include "cyber/record/record_viewer.h" #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace record { RecordViewer::RecordViewer(const std::shared_ptr& reader, @@ -117,5 +117,5 @@ RecordViewer::Iterator::reference RecordViewer::Iterator::operator*() { } } // namespace record -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/record/record_viewer.h b/cyber/record/record_viewer.h similarity index 89% rename from cybertron/record/record_viewer.h rename to cyber/record/record_viewer.h index fc2dad5d2b4..ce57bc23ba2 100644 --- a/cybertron/record/record_viewer.h +++ b/cyber/record/record_viewer.h @@ -14,18 +14,18 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_RECORD_RECORD_VIEWER_H_ -#define CYBERTRON_RECORD_RECORD_VIEWER_H_ +#ifndef CYBER_RECORD_RECORD_VIEWER_H_ +#define CYBER_RECORD_RECORD_VIEWER_H_ #include #include #include -#include "cybertron/record/record_message.h" -#include "cybertron/record/record_reader.h" +#include "cyber/record/record_message.h" +#include "cyber/record/record_reader.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace record { class RecordMessage; @@ -78,7 +78,7 @@ class RecordViewer { }; } // namespace record -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_RECORD_RECORD_READER_H_ +#endif // CYBER_RECORD_RECORD_READER_H_ diff --git a/cybertron/record/record_writer.cc b/cyber/record/record_writer.cc similarity index 98% rename from cybertron/record/record_writer.cc rename to cyber/record/record_writer.cc index e91ada83313..134c643a9bd 100644 --- a/cybertron/record/record_writer.cc +++ b/cyber/record/record_writer.cc @@ -14,15 +14,15 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/record/record_writer.h" +#include "cyber/record/record_writer.h" #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace record { using proto::Channel; @@ -207,5 +207,5 @@ const std::string& RecordWriter::GetProtoDesc( } } // namespace record -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/record/record_writer.h b/cyber/record/record_writer.h similarity index 92% rename from cybertron/record/record_writer.h rename to cyber/record/record_writer.h index cb814d4c929..06b4dfdcd23 100644 --- a/cybertron/record/record_writer.h +++ b/cyber/record/record_writer.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_RECORD_RECORD_WRITER_H_ -#define CYBERTRON_RECORD_RECORD_WRITER_H_ +#ifndef CYBER_RECORD_RECORD_WRITER_H_ +#define CYBER_RECORD_RECORD_WRITER_H_ #include #include @@ -24,15 +24,15 @@ #include #include -#include "cybertron/common/log.h" -#include "cybertron/message/raw_message.h" -#include "cybertron/proto/record.pb.h" -#include "cybertron/record/header_builder.h" -#include "cybertron/record/record_base.h" -#include "cybertron/record/record_file.h" +#include "cyber/common/log.h" +#include "cyber/message/raw_message.h" +#include "cyber/proto/record.pb.h" +#include "cyber/record/header_builder.h" +#include "cyber/record/record_base.h" +#include "cyber/record/record_file.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace record { class RecordWriter : public RecordBase { @@ -148,7 +148,7 @@ bool RecordWriter::WriteMessage(const std::string& channel_name, } } // namespace record -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_RECORD_RECORD_WRITER_H_ +#endif // CYBER_RECORD_RECORD_WRITER_H_ diff --git a/cybertron/scheduler/BUILD b/cyber/scheduler/BUILD similarity index 82% rename from cybertron/scheduler/BUILD rename to cyber/scheduler/BUILD index 3cc9b636205..1e7973f833d 100644 --- a/cybertron/scheduler/BUILD +++ b/cyber/scheduler/BUILD @@ -19,9 +19,9 @@ cc_library( "policy/classic.h", ], deps = [ - "//cybertron/croutine:croutine", - "//cybertron/data:data", - "//cybertron/proto:component_config_cc_proto", + "//cyber/croutine:croutine", + "//cyber/data:data", + "//cyber/proto:component_config_cc_proto", ], ) @@ -32,7 +32,7 @@ cc_test( "scheduler_test.cc", ], deps = [ - "//cybertron", + "//cyber", "@gtest//:main", ], ) @@ -44,7 +44,7 @@ cc_test( "scheduler_policy_test.cc", ], deps = [ - "//cybertron", + "//cyber", "@gtest//:main", ], ) diff --git a/cybertron/scheduler/policy/classic.cc b/cyber/scheduler/policy/classic.cc similarity index 87% rename from cybertron/scheduler/policy/classic.cc rename to cyber/scheduler/policy/classic.cc index 1096c066d1b..9a96ecd2e25 100644 --- a/cybertron/scheduler/policy/classic.cc +++ b/cyber/scheduler/policy/classic.cc @@ -14,21 +14,21 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/scheduler/policy/classic.h" +#include "cyber/scheduler/policy/classic.h" #include #include -#include "cybertron/event/perf_event_cache.h" -#include "cybertron/scheduler/processor.h" -#include "cybertron/scheduler/scheduler.h" +#include "cyber/event/perf_event_cache.h" +#include "cyber/scheduler/processor.h" +#include "cyber/scheduler/scheduler.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace scheduler { -using apollo::cybertron::event::PerfEventCache; -using apollo::cybertron::event::SchedPerf; +using apollo::cyber::event::PerfEventCache; +using apollo::cyber::event::SchedPerf; std::mutex ClassicContext::mtx_taskq_; std::mutex ClassicContext::mtx_rq_; @@ -67,7 +67,7 @@ std::shared_ptr ClassicContext::NextRoutine() { } std::lock_guard lk(mtx_rq_); std::shared_ptr croutine = nullptr; - auto start_perf_time = apollo::cybertron::Time::Now().ToNanosecond(); + auto start_perf_time = apollo::cyber::Time::Now().ToNanosecond(); auto p = rq_.begin(); for (; p != rq_.end();) { auto cr = p->second; @@ -97,5 +97,5 @@ std::shared_ptr ClassicContext::NextRoutine() { bool ClassicContext::RqEmpty() { return rq_.empty(); } } // namespace scheduler -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/scheduler/policy/classic.h b/cyber/scheduler/policy/classic.h similarity index 86% rename from cybertron/scheduler/policy/classic.h rename to cyber/scheduler/policy/classic.h index 86578f5961c..52fd14b72bd 100644 --- a/cybertron/scheduler/policy/classic.h +++ b/cyber/scheduler/policy/classic.h @@ -14,18 +14,18 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_SCHEDULER_POLICY_CLASSIC_H_ -#define CYBERTRON_SCHEDULER_POLICY_CLASSIC_H_ +#ifndef CYBER_SCHEDULER_POLICY_CLASSIC_H_ +#define CYBER_SCHEDULER_POLICY_CLASSIC_H_ #include #include #include #include -#include "cybertron/scheduler/processor_context.h" +#include "cyber/scheduler/processor_context.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace scheduler { using croutine::CRoutine; @@ -50,7 +50,7 @@ class ClassicContext : public ProcessorContext { }; } // namespace scheduler -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_SCHEDULER_POLICY_CLASSIC_CONTEXT_H_ +#endif // CYBER_SCHEDULER_POLICY_CLASSIC_CONTEXT_H_ diff --git a/cybertron/scheduler/policy/task_choreo.cc b/cyber/scheduler/policy/task_choreo.cc similarity index 76% rename from cybertron/scheduler/policy/task_choreo.cc rename to cyber/scheduler/policy/task_choreo.cc index bf1a36e8410..b728eb18513 100644 --- a/cybertron/scheduler/policy/task_choreo.cc +++ b/cyber/scheduler/policy/task_choreo.cc @@ -14,28 +14,28 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/scheduler/policy/task_choreo.h" +#include "cyber/scheduler/policy/task_choreo.h" #include -#include "cybertron/common/log.h" -#include "cybertron/common/types.h" -#include "cybertron/croutine/croutine.h" -#include "cybertron/event/perf_event_cache.h" -#include "cybertron/proto/routine_conf.pb.h" -#include "cybertron/proto/scheduler_conf.pb.h" -#include "cybertron/scheduler/processor.h" -#include "cybertron/time/time.h" +#include "cyber/common/log.h" +#include "cyber/common/types.h" +#include "cyber/croutine/croutine.h" +#include "cyber/event/perf_event_cache.h" +#include "cyber/proto/routine_conf.pb.h" +#include "cyber/proto/scheduler_conf.pb.h" +#include "cyber/scheduler/processor.h" +#include "cyber/time/time.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace scheduler { -using apollo::cybertron::event::PerfEventCache; -using apollo::cybertron::event::SchedPerf; -using apollo::cybertron::proto::RoutineConf; -using apollo::cybertron::proto::RoutineConfInfo; -using apollo::cybertron::proto::SchedulerConf; +using apollo::cyber::event::PerfEventCache; +using apollo::cyber::event::SchedPerf; +using apollo::cyber::proto::RoutineConf; +using apollo::cyber::proto::RoutineConfInfo; +using apollo::cyber::proto::SchedulerConf; using croutine::RoutineState; std::shared_ptr TaskChoreoContext::NextRoutine() { @@ -44,7 +44,7 @@ std::shared_ptr TaskChoreoContext::NextRoutine() { } std::lock_guard lock(mtx_run_queue_); - auto start_perf_time = apollo::cybertron::Time::Now().ToNanosecond(); + auto start_perf_time = apollo::cyber::Time::Now().ToNanosecond(); std::shared_ptr croutine = nullptr; for (auto it = rt_queue_.begin(); it != rt_queue_.end();) { @@ -105,5 +105,5 @@ bool TaskChoreoContext::RqEmpty() { } } // namespace scheduler -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/scheduler/policy/task_choreo.h b/cyber/scheduler/policy/task_choreo.h similarity index 84% rename from cybertron/scheduler/policy/task_choreo.h rename to cyber/scheduler/policy/task_choreo.h index c8bda53db94..0e7d8fe0be7 100644 --- a/cybertron/scheduler/policy/task_choreo.h +++ b/cyber/scheduler/policy/task_choreo.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_SCHEDULER_POLICY_TASK_CHOREO_CONTEXT_H_ -#define CYBERTRON_SCHEDULER_POLICY_TASK_CHOREO_CONTEXT_H_ +#ifndef CYBER_SCHEDULER_POLICY_TASK_CHOREO_CONTEXT_H_ +#define CYBER_SCHEDULER_POLICY_TASK_CHOREO_CONTEXT_H_ #include #include @@ -24,10 +24,10 @@ #include #include -#include "cybertron/scheduler/processor_context.h" +#include "cyber/scheduler/processor_context.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace croutine { class CRoutine; } @@ -52,7 +52,7 @@ class TaskChoreoContext : public ProcessorContext { }; } // namespace scheduler -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_SCHEDULER_POLICY_CHOREO_CONTEXT_H_ +#endif // CYBER_SCHEDULER_POLICY_CHOREO_CONTEXT_H_ diff --git a/cybertron/scheduler/processor.cc b/cyber/scheduler/processor.cc similarity index 85% rename from cybertron/scheduler/processor.cc rename to cyber/scheduler/processor.cc index a96e6e012a7..ec3ef6c34a2 100644 --- a/cybertron/scheduler/processor.cc +++ b/cyber/scheduler/processor.cc @@ -17,17 +17,17 @@ #include #include -#include "cybertron/common/global_data.h" -#include "cybertron/common/log.h" -#include "cybertron/croutine/croutine.h" -#include "cybertron/croutine/routine_context.h" -#include "cybertron/scheduler/processor.h" -#include "cybertron/scheduler/processor_context.h" -#include "cybertron/scheduler/scheduler.h" -#include "cybertron/time/time.h" +#include "cyber/common/global_data.h" +#include "cyber/common/log.h" +#include "cyber/croutine/croutine.h" +#include "cyber/croutine/routine_context.h" +#include "cyber/scheduler/processor.h" +#include "cyber/scheduler/processor_context.h" +#include "cyber/scheduler/scheduler.h" +#include "cyber/time/time.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace scheduler { Processor::Processor() { routine_context_.reset(new RoutineContext()); } @@ -80,5 +80,5 @@ void Processor::Run() { } } // namespace scheduler -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/scheduler/processor.h b/cyber/scheduler/processor.h similarity index 85% rename from cybertron/scheduler/processor.h rename to cyber/scheduler/processor.h index 5f3d6f6c40a..51604a979d9 100644 --- a/cybertron/scheduler/processor.h +++ b/cyber/scheduler/processor.h @@ -14,27 +14,27 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_SCHEDULER_PROCESSOR_H_ -#define CYBERTRON_SCHEDULER_PROCESSOR_H_ +#ifndef CYBER_SCHEDULER_PROCESSOR_H_ +#define CYBER_SCHEDULER_PROCESSOR_H_ #include #include #include #include -#include "cybertron/croutine/croutine.h" -#include "cybertron/croutine/routine_context.h" -#include "cybertron/proto/scheduler_conf.pb.h" +#include "cyber/croutine/croutine.h" +#include "cyber/croutine/routine_context.h" +#include "cyber/proto/scheduler_conf.pb.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace scheduler { class ProcessorContext; using croutine::CRoutine; using croutine::RoutineContext; -using apollo::cybertron::proto::ProcessStrategy; +using apollo::cyber::proto::ProcessStrategy; struct ProcessorStat { uint64_t switch_num = 0; @@ -79,7 +79,7 @@ class Processor { }; } // namespace scheduler -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_SCHEDULER_PROCESSOR_H_ +#endif // CYBER_SCHEDULER_PROCESSOR_H_ diff --git a/cybertron/scheduler/processor_context.cc b/cyber/scheduler/processor_context.cc similarity index 80% rename from cybertron/scheduler/processor_context.cc rename to cyber/scheduler/processor_context.cc index 7aea8de832d..5a4fb1be503 100644 --- a/cybertron/scheduler/processor_context.cc +++ b/cyber/scheduler/processor_context.cc @@ -14,22 +14,22 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/scheduler/processor.h" +#include "cyber/scheduler/processor.h" -#include "cybertron/common/log.h" -#include "cybertron/common/types.h" -#include "cybertron/croutine/croutine.h" -#include "cybertron/event/perf_event_cache.h" -#include "cybertron/scheduler/processor_context.h" -#include "cybertron/scheduler/scheduler.h" -#include "cybertron/time/time.h" +#include "cyber/common/log.h" +#include "cyber/common/types.h" +#include "cyber/croutine/croutine.h" +#include "cyber/event/perf_event_cache.h" +#include "cyber/scheduler/processor_context.h" +#include "cyber/scheduler/scheduler.h" +#include "cyber/time/time.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace scheduler { -using apollo::cybertron::event::PerfEventCache; -using apollo::cybertron::event::SchedPerf; +using apollo::cyber::event::PerfEventCache; +using apollo::cyber::event::SchedPerf; void ProcessorContext::RemoveCRoutine(uint64_t croutine_id) { WriteLockGuard lg(rw_lock_); @@ -72,5 +72,5 @@ void ProcessorContext::ShutDown() { } } // namespace scheduler -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/scheduler/processor_context.h b/cyber/scheduler/processor_context.h similarity index 84% rename from cybertron/scheduler/processor_context.h rename to cyber/scheduler/processor_context.h index 440c81b607a..3f145245f42 100644 --- a/cybertron/scheduler/processor_context.h +++ b/cyber/scheduler/processor_context.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_SCHEDULER_POLICY_PROCESSOR_CONTEXT_H_ -#define CYBERTRON_SCHEDULER_POLICY_PROCESSOR_CONTEXT_H_ +#ifndef CYBER_SCHEDULER_POLICY_PROCESSOR_CONTEXT_H_ +#define CYBER_SCHEDULER_POLICY_PROCESSOR_CONTEXT_H_ #include #include @@ -26,18 +26,18 @@ #include #include -#include "cybertron/base/atomic_hash_map.h" -#include "cybertron/base/atomic_rw_lock.h" -#include "cybertron/croutine/croutine.h" +#include "cyber/base/atomic_hash_map.h" +#include "cyber/base/atomic_rw_lock.h" +#include "cyber/croutine/croutine.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace scheduler { -using apollo::cybertron::base::AtomicHashMap; -using apollo::cybertron::base::AtomicRWLock; -using apollo::cybertron::base::ReadLockGuard; -using apollo::cybertron::base::WriteLockGuard; +using apollo::cyber::base::AtomicHashMap; +using apollo::cyber::base::AtomicRWLock; +using apollo::cyber::base::ReadLockGuard; +using apollo::cyber::base::WriteLockGuard; using croutine::CRoutine; using croutine::RoutineState; using CRoutineList = std::list>; @@ -110,7 +110,7 @@ bool ProcessorContext::set_state(const uint64_t& routine_id, } } // namespace scheduler -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_SCHEDULER_POLICY_PROCESSOR_CONTEXT_H_ +#endif // CYBER_SCHEDULER_POLICY_PROCESSOR_CONTEXT_H_ diff --git a/cybertron/scheduler/scheduler.cc b/cyber/scheduler/scheduler.cc similarity index 93% rename from cybertron/scheduler/scheduler.cc rename to cyber/scheduler/scheduler.cc index 26eef993044..07fc7b073e3 100644 --- a/cybertron/scheduler/scheduler.cc +++ b/cyber/scheduler/scheduler.cc @@ -13,24 +13,24 @@ * See the License for the specific language governing permissions and * limitations under the License. *****************************************************************************/ -#include "cybertron/scheduler/scheduler.h" +#include "cyber/scheduler/scheduler.h" #include -#include "cybertron/common/global_data.h" -#include "cybertron/common/util.h" -#include "cybertron/data/data_visitor.h" -#include "cybertron/scheduler/policy/classic.h" -#include "cybertron/scheduler/policy/task_choreo.h" -#include "cybertron/scheduler/processor.h" -#include "cybertron/scheduler/processor_context.h" +#include "cyber/common/global_data.h" +#include "cyber/common/util.h" +#include "cyber/data/data_visitor.h" +#include "cyber/scheduler/policy/classic.h" +#include "cyber/scheduler/policy/task_choreo.h" +#include "cyber/scheduler/processor.h" +#include "cyber/scheduler/processor_context.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace scheduler { -using apollo::cybertron::proto::RoutineConfInfo; -using apollo::cybertron::common::GlobalData; +using apollo::cyber::proto::RoutineConfInfo; +using apollo::cyber::common::GlobalData; Scheduler::Scheduler() : stop_(false) { auto gconf = GlobalData::Instance()->Config(); @@ -293,5 +293,5 @@ bool Scheduler::RemoveCRoutine(uint64_t cr_id) { void Scheduler::PrintStatistics() {} } // namespace scheduler -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/scheduler/scheduler.h b/cyber/scheduler/scheduler.h similarity index 78% rename from cybertron/scheduler/scheduler.h rename to cyber/scheduler/scheduler.h index 4ed271ed9c3..b1424143242 100644 --- a/cybertron/scheduler/scheduler.h +++ b/cyber/scheduler/scheduler.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_SCHEDULER_SCHEDULER_H_ -#define CYBERTRON_SCHEDULER_SCHEDULER_H_ +#ifndef CYBER_SCHEDULER_SCHEDULER_H_ +#define CYBER_SCHEDULER_SCHEDULER_H_ #include #include @@ -28,24 +28,24 @@ #include #include -#include "cybertron/common/log.h" -#include "cybertron/common/macros.h" -#include "cybertron/common/types.h" -#include "cybertron/croutine/croutine.h" -#include "cybertron/croutine/routine_factory.h" -#include "cybertron/proto/routine_conf.pb.h" -#include "cybertron/proto/scheduler_conf.pb.h" +#include "cyber/common/log.h" +#include "cyber/common/macros.h" +#include "cyber/common/types.h" +#include "cyber/croutine/croutine.h" +#include "cyber/croutine/routine_factory.h" +#include "cyber/proto/routine_conf.pb.h" +#include "cyber/proto/scheduler_conf.pb.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace scheduler { -using apollo::cybertron::proto::RoutineConf; -using apollo::cybertron::proto::SchedulerConf; -using apollo::cybertron::croutine::CRoutine; -using apollo::cybertron::croutine::RoutineFactory; -using apollo::cybertron::data::DataVisitorBase; -using apollo::cybertron::proto::ProcessStrategy; +using apollo::cyber::proto::RoutineConf; +using apollo::cyber::proto::SchedulerConf; +using apollo::cyber::croutine::CRoutine; +using apollo::cyber::croutine::RoutineFactory; +using apollo::cyber::data::DataVisitorBase; +using apollo::cyber::proto::ProcessStrategy; class ProcessorContext; @@ -97,7 +97,7 @@ class Scheduler { }; } // namespace scheduler -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_SCHEDULER_SCHEDULER_H_ +#endif // CYBER_SCHEDULER_SCHEDULER_H_ diff --git a/cybertron/scheduler/scheduler_policy_test.cc b/cyber/scheduler/scheduler_policy_test.cc similarity index 85% rename from cybertron/scheduler/scheduler_policy_test.cc rename to cyber/scheduler/scheduler_policy_test.cc index 5a0b3c264c6..4f655ef1114 100644 --- a/cybertron/scheduler/scheduler_policy_test.cc +++ b/cyber/scheduler/scheduler_policy_test.cc @@ -17,13 +17,13 @@ #include #include -#include "cybertron/common/util.h" -#include "cybertron/cybertron.h" -#include "cybertron/scheduler/policy/task_choreo.h" -#include "cybertron/scheduler/processor.h" +#include "cyber/common/util.h" +#include "cyber/cyber.h" +#include "cyber/scheduler/policy/task_choreo.h" +#include "cyber/scheduler/processor.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace scheduler { void func() {} @@ -40,5 +40,5 @@ TEST(SchedulerPolicyTest, choreo) { } } // namespace scheduler -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/scheduler/scheduler_test.cc b/cyber/scheduler/scheduler_test.cc similarity index 85% rename from cybertron/scheduler/scheduler_test.cc rename to cyber/scheduler/scheduler_test.cc index e19049ad338..1a010a42373 100644 --- a/cybertron/scheduler/scheduler_test.cc +++ b/cyber/scheduler/scheduler_test.cc @@ -17,12 +17,12 @@ #include #include -#include "cybertron/croutine/routine_factory.h" -#include "cybertron/cybertron.h" -#include "cybertron/scheduler/scheduler.h" +#include "cyber/croutine/routine_factory.h" +#include "cyber/cyber.h" +#include "cyber/scheduler/scheduler.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace scheduler { auto sched = Scheduler::Instance(); @@ -30,11 +30,11 @@ auto sched = Scheduler::Instance(); void proc() {} TEST(SchedulerTest, create_task) { - cybertron::Init(); + cyber::Init(); std::string croutine_name = "DriverProc"; EXPECT_TRUE(sched->CreateTask(&proc, croutine_name)); } } // namespace scheduler -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/service/BUILD b/cyber/service/BUILD similarity index 100% rename from cybertron/service/BUILD rename to cyber/service/BUILD diff --git a/cybertron/service/client.h b/cyber/service/client.h similarity index 96% rename from cybertron/service/client.h rename to cyber/service/client.h index d269a71cf14..c3f7cb00bcf 100644 --- a/cybertron/service/client.h +++ b/cyber/service/client.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_SERVICE_CLIENT_H_ -#define CYBERTRON_SERVICE_CLIENT_H_ +#ifndef CYBER_SERVICE_CLIENT_H_ +#define CYBER_SERVICE_CLIENT_H_ #include #include @@ -26,14 +26,14 @@ #include #include -#include "cybertron/common/log.h" -#include "cybertron/common/types.h" +#include "cyber/common/log.h" +#include "cyber/common/types.h" -#include "cybertron/node/node_channel_impl.h" -#include "cybertron/service/client_base.h" +#include "cyber/node/node_channel_impl.h" +#include "cyber/service/client_base.h" namespace apollo { -namespace cybertron { +namespace cyber { template class Client : public ClientBase { @@ -227,7 +227,7 @@ void Client::HandleResponse( callback(future); } -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_SERVICE_CLIENT_H_ +#endif // CYBER_SERVICE_CLIENT_H_ diff --git a/cybertron/service/client_base.h b/cyber/service/client_base.h similarity index 89% rename from cybertron/service/client_base.h rename to cyber/service/client_base.h index 4324d1feeaa..3ff90f940c8 100644 --- a/cybertron/service/client_base.h +++ b/cyber/service/client_base.h @@ -14,16 +14,16 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_SERVICE_CLIENT_BASE_H_ -#define CYBERTRON_SERVICE_CLIENT_BASE_H_ +#ifndef CYBER_SERVICE_CLIENT_BASE_H_ +#define CYBER_SERVICE_CLIENT_BASE_H_ #include #include -#include "cybertron/common/macros.h" +#include "cyber/common/macros.h" namespace apollo { -namespace cybertron { +namespace cyber { class ClientBase { public: @@ -58,7 +58,7 @@ class ClientBase { } }; -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_SERVICE_CLIENT_BASE_H_ +#endif // CYBER_SERVICE_CLIENT_BASE_H_ diff --git a/cybertron/service/service.h b/cyber/service/service.h similarity index 94% rename from cybertron/service/service.h rename to cyber/service/service.h index 24360c75a95..3ba18285efd 100644 --- a/cybertron/service/service.h +++ b/cyber/service/service.h @@ -14,18 +14,18 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_SERVICE_SERVICE_H_ -#define CYBERTRON_SERVICE_SERVICE_H_ +#ifndef CYBER_SERVICE_SERVICE_H_ +#define CYBER_SERVICE_SERVICE_H_ #include #include -#include "cybertron/common/types.h" -#include "cybertron/node/node_channel_impl.h" -#include "cybertron/service/service_base.h" +#include "cyber/common/types.h" +#include "cyber/node/node_channel_impl.h" +#include "cyber/service/service_base.h" namespace apollo { -namespace cybertron { +namespace cyber { template class Service : public ServiceBase { @@ -153,7 +153,7 @@ void Service::SendResponse( response_transmitter_->Transmit(response, message_info); } -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_SERVICE_SERVICE_H_ +#endif // CYBER_SERVICE_SERVICE_H_ diff --git a/cybertron/service/service_base.h b/cyber/service/service_base.h similarity index 86% rename from cybertron/service/service_base.h rename to cyber/service/service_base.h index db801c0ee79..5fed9312770 100644 --- a/cybertron/service/service_base.h +++ b/cyber/service/service_base.h @@ -14,13 +14,13 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_SERVICE_SERVICE_BASE_H_ -#define CYBERTRON_SERVICE_SERVICE_BASE_H_ +#ifndef CYBER_SERVICE_SERVICE_BASE_H_ +#define CYBER_SERVICE_SERVICE_BASE_H_ #include namespace apollo { -namespace cybertron { +namespace cyber { class ServiceBase { public: @@ -37,7 +37,7 @@ class ServiceBase { std::string service_name_; }; -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_SERVICE_SERVICE_BASE_H_ +#endif // CYBER_SERVICE_SERVICE_BASE_H_ diff --git a/cybertron/service_discovery/BUILD b/cyber/service_discovery/BUILD similarity index 78% rename from cybertron/service_discovery/BUILD rename to cyber/service_discovery/BUILD index 6c7314f7d8c..b1383dd3836 100644 --- a/cybertron/service_discovery/BUILD +++ b/cyber/service_discovery/BUILD @@ -11,7 +11,7 @@ cc_library( "channel_manager", "node_manager", "service_manager", - "//cybertron:init", + "//cyber:init", ], ) @@ -20,7 +20,7 @@ cc_test( size = "small", srcs = [ "topology_manager_test.cc", ], deps = [ - "//cybertron", + "//cyber", "@gtest//:main", ], ) @@ -30,7 +30,7 @@ cc_library( srcs = [ "communication/participant_listener.cc", ], hdrs = [ "communication/participant_listener.h", ], deps = [ - "//cybertron/transport/rtps:rtps_lib", + "//cyber/transport/rtps:rtps_lib", ], ) @@ -39,7 +39,7 @@ cc_library( srcs = [ "communication/subscriber_listener.cc", ], hdrs = [ "communication/subscriber_listener.h", ], deps = [ - "//cybertron/transport/rtps:rtps_lib", + "//cyber/transport/rtps:rtps_lib", ], ) @@ -47,7 +47,7 @@ cc_library( name = "graph", srcs = [ "container/graph.cc", ], hdrs = [ "container/graph.h", ], - deps = [ "//cybertron/base:atomic_rw_lock", ], + deps = [ "//cyber/base:atomic_rw_lock", ], ) cc_test( @@ -55,7 +55,7 @@ cc_test( size = "small", srcs = [ "container/graph_test.cc", ], deps = [ - "//cybertron", + "//cyber", "@gtest//:main", ], ) @@ -66,7 +66,7 @@ cc_library( hdrs = [ "container/multi_value_warehouse.h", ], deps = [ "warehouse_base", - "//cybertron/base:atomic_rw_lock", + "//cyber/base:atomic_rw_lock", ], ) @@ -76,7 +76,7 @@ cc_library( hdrs = [ "container/single_value_warehouse.h", ], deps = [ "warehouse_base", - "//cybertron/base:atomic_rw_lock", + "//cyber/base:atomic_rw_lock", ], ) @@ -91,10 +91,10 @@ cc_library( srcs = [ "role/role.cc", ], hdrs = [ "role/role.h", ], deps = [ - "//cybertron:binary", - "//cybertron/common:log", - "//cybertron/common:types", - "//cybertron/proto:role_attributes_cc_proto", + "//cyber:binary", + "//cyber/common:log", + "//cyber/common:types", + "//cyber/proto:role_attributes_cc_proto", ], ) @@ -103,7 +103,7 @@ cc_test( size = "small", srcs = [ "role/role_test.cc", ], deps = [ - "//cybertron", + "//cyber", "@gtest//:main", ], ) @@ -114,13 +114,13 @@ cc_library( hdrs = [ "specific_manager/manager.h", ], deps = [ "subscriber_listener", - "//cybertron/base:signal", - "//cybertron/message:message_traits", - "//cybertron/message:protobuf_factory", - "//cybertron/proto:proto_desc_cc_proto", - "//cybertron/proto:role_attributes_cc_proto", - "//cybertron/proto:topology_change_cc_proto", - "//cybertron/time:time", + "//cyber/base:signal", + "//cyber/message:message_traits", + "//cyber/message:protobuf_factory", + "//cyber/proto:proto_desc_cc_proto", + "//cyber/proto:role_attributes_cc_proto", + "//cyber/proto:topology_change_cc_proto", + "//cyber/time:time", ], ) @@ -141,8 +141,8 @@ cc_test( size = "small", srcs = [ "specific_manager/channel_manager_test.cc", ], deps = [ - "//cybertron", - "//cybertron/proto:chatter_cc_proto", + "//cyber", + "//cyber/proto:chatter_cc_proto", "@gtest//:main", ], ) @@ -163,7 +163,7 @@ cc_test( size = "small", srcs = [ "specific_manager/node_manager_test.cc", ], deps = [ - "//cybertron", + "//cyber", "@gtest//:main", ], ) @@ -184,7 +184,7 @@ cc_test( size = "small", srcs = [ "specific_manager/service_manager_test.cc", ], deps = [ - "//cybertron", + "//cyber", "@gtest//:main", ], ) diff --git a/cybertron/service_discovery/communication/participant_listener.cc b/cyber/service_discovery/communication/participant_listener.cc similarity index 89% rename from cybertron/service_discovery/communication/participant_listener.cc rename to cyber/service_discovery/communication/participant_listener.cc index f5b7fb4a919..efee01f9262 100644 --- a/cybertron/service_discovery/communication/participant_listener.cc +++ b/cyber/service_discovery/communication/participant_listener.cc @@ -14,12 +14,12 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/service_discovery/communication/participant_listener.h" +#include "cyber/service_discovery/communication/participant_listener.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace service_discovery { ParticipantListener::ParticipantListener(const ChangeFunc& callback) @@ -39,5 +39,5 @@ void ParticipantListener::onParticipantDiscovery( } } // namespace service_discovery -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/service_discovery/communication/participant_listener.h b/cyber/service_discovery/communication/participant_listener.h similarity index 84% rename from cybertron/service_discovery/communication/participant_listener.h rename to cyber/service_discovery/communication/participant_listener.h index 040c1593f72..91cc20d70bd 100644 --- a/cybertron/service_discovery/communication/participant_listener.h +++ b/cyber/service_discovery/communication/participant_listener.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_SERVICE_DISCOVERY_COMMUNICATION_PARTICIPANT_LISTENER_H_ -#define CYBERTRON_SERVICE_DISCOVERY_COMMUNICATION_PARTICIPANT_LISTENER_H_ +#ifndef CYBER_SERVICE_DISCOVERY_COMMUNICATION_PARTICIPANT_LISTENER_H_ +#define CYBER_SERVICE_DISCOVERY_COMMUNICATION_PARTICIPANT_LISTENER_H_ #include #include @@ -25,7 +25,7 @@ #include "fastrtps/participant/ParticipantListener.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace service_discovery { class ParticipantListener : public eprosima::fastrtps::ParticipantListener { @@ -46,7 +46,7 @@ class ParticipantListener : public eprosima::fastrtps::ParticipantListener { }; } // namespace service_discovery -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_SERVICE_DISCOVERY_COMMUNICATION_PARTICIPANT_LISTENER_H_ +#endif // CYBER_SERVICE_DISCOVERY_COMMUNICATION_PARTICIPANT_LISTENER_H_ diff --git a/cybertron/service_discovery/communication/subscriber_listener.cc b/cyber/service_discovery/communication/subscriber_listener.cc similarity index 83% rename from cybertron/service_discovery/communication/subscriber_listener.cc rename to cyber/service_discovery/communication/subscriber_listener.cc index f325d30cc98..1501b5ab880 100644 --- a/cybertron/service_discovery/communication/subscriber_listener.cc +++ b/cyber/service_discovery/communication/subscriber_listener.cc @@ -14,14 +14,14 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/service_discovery/communication/subscriber_listener.h" +#include "cyber/service_discovery/communication/subscriber_listener.h" -#include "cybertron/common/log.h" -#include "cybertron/transport/rtps/underlay_message.h" -#include "cybertron/transport/rtps/underlay_message_type.h" +#include "cyber/common/log.h" +#include "cyber/transport/rtps/underlay_message.h" +#include "cyber/transport/rtps/underlay_message_type.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace service_discovery { SubscriberListener::SubscriberListener(const NewMsgCallback& callback) @@ -37,7 +37,7 @@ void SubscriberListener::onNewDataMessage(eprosima::fastrtps::Subscriber* sub) { std::lock_guard lock(mutex_); eprosima::fastrtps::SampleInfo_t m_info; - cybertron::transport::UnderlayMessage m; + cyber::transport::UnderlayMessage m; RETURN_IF(!sub->takeNextData(reinterpret_cast(&m), &m_info)); RETURN_IF(m_info.sampleKind != eprosima::fastrtps::ALIVE); @@ -52,5 +52,5 @@ void SubscriberListener::onSubscriptionMatched( } } // namespace service_discovery -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/service_discovery/communication/subscriber_listener.h b/cyber/service_discovery/communication/subscriber_listener.h similarity index 85% rename from cybertron/service_discovery/communication/subscriber_listener.h rename to cyber/service_discovery/communication/subscriber_listener.h index 9e89b609325..1c63c1f6a02 100644 --- a/cybertron/service_discovery/communication/subscriber_listener.h +++ b/cyber/service_discovery/communication/subscriber_listener.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_SERVICE_DISCOVERY_COMMUNICATION_SUBSCRIBER_LISTENER_H_ -#define CYBERTRON_SERVICE_DISCOVERY_COMMUNICATION_SUBSCRIBER_LISTENER_H_ +#ifndef CYBER_SERVICE_DISCOVERY_COMMUNICATION_SUBSCRIBER_LISTENER_H_ +#define CYBER_SERVICE_DISCOVERY_COMMUNICATION_SUBSCRIBER_LISTENER_H_ #include #include @@ -27,7 +27,7 @@ #include "fastrtps/subscriber/SubscriberListener.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace service_discovery { class SubscriberListener : public eprosima::fastrtps::SubscriberListener { @@ -47,7 +47,7 @@ class SubscriberListener : public eprosima::fastrtps::SubscriberListener { }; } // namespace service_discovery -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_SERVICE_DISCOVERY_COMMUNICATION_SUBSCRIBER_LISTENER_H_ +#endif // CYBER_SERVICE_DISCOVERY_COMMUNICATION_SUBSCRIBER_LISTENER_H_ diff --git a/cybertron/service_discovery/container/graph.cc b/cyber/service_discovery/container/graph.cc similarity index 98% rename from cybertron/service_discovery/container/graph.cc rename to cyber/service_discovery/container/graph.cc index 154dcb13e34..f1184bd7716 100644 --- a/cybertron/service_discovery/container/graph.cc +++ b/cyber/service_discovery/container/graph.cc @@ -14,12 +14,12 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/service_discovery/container/graph.h" +#include "cyber/service_discovery/container/graph.h" #include namespace apollo { -namespace cybertron { +namespace cyber { namespace service_discovery { Vertice::Vertice(const std::string& val) : value_(val) {} @@ -278,5 +278,5 @@ bool Graph::LevelTraverse(const Vertice& start, const Vertice& end) { } } // namespace service_discovery -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/service_discovery/container/graph.h b/cyber/service_discovery/container/graph.h similarity index 89% rename from cybertron/service_discovery/container/graph.h rename to cyber/service_discovery/container/graph.h index 1c356ac480b..627a9c600f3 100644 --- a/cybertron/service_discovery/container/graph.h +++ b/cyber/service_discovery/container/graph.h @@ -14,22 +14,22 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_SERVICE_DISCOVERY_ROLE_GRAPH_H_ -#define CYBERTRON_SERVICE_DISCOVERY_ROLE_GRAPH_H_ +#ifndef CYBER_SERVICE_DISCOVERY_ROLE_GRAPH_H_ +#define CYBER_SERVICE_DISCOVERY_ROLE_GRAPH_H_ #include #include #include -#include "cybertron/base/atomic_rw_lock.h" +#include "cyber/base/atomic_rw_lock.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace service_discovery { -using apollo::cybertron::base::AtomicRWLock; -using apollo::cybertron::base::ReadLockGuard; -using apollo::cybertron::base::WriteLockGuard; +using apollo::cyber::base::AtomicRWLock; +using apollo::cyber::base::ReadLockGuard; +using apollo::cyber::base::WriteLockGuard; /** * @brief describe the flow direction between nodes @@ -131,7 +131,7 @@ class Graph { }; } // namespace service_discovery -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_SERVICE_DISCOVERY_ROLE_GRAPH_H_ +#endif // CYBER_SERVICE_DISCOVERY_ROLE_GRAPH_H_ diff --git a/cybertron/service_discovery/container/graph_test.cc b/cyber/service_discovery/container/graph_test.cc similarity index 97% rename from cybertron/service_discovery/container/graph_test.cc rename to cyber/service_discovery/container/graph_test.cc index dca8d7c8029..c208380d89d 100644 --- a/cybertron/service_discovery/container/graph_test.cc +++ b/cyber/service_discovery/container/graph_test.cc @@ -17,10 +17,10 @@ #include #include -#include "cybertron/service_discovery/container/graph.h" +#include "cyber/service_discovery/container/graph.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace service_discovery { TEST(GraphTest, vertice) { @@ -206,5 +206,5 @@ TEST(GraphTest, graph) { } } // namespace service_discovery -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/service_discovery/container/multi_value_warehouse.cc b/cyber/service_discovery/container/multi_value_warehouse.cc similarity index 97% rename from cybertron/service_discovery/container/multi_value_warehouse.cc rename to cyber/service_discovery/container/multi_value_warehouse.cc index 59cb296ae46..17603c51bd8 100644 --- a/cybertron/service_discovery/container/multi_value_warehouse.cc +++ b/cyber/service_discovery/container/multi_value_warehouse.cc @@ -14,15 +14,15 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/service_discovery/container/multi_value_warehouse.h" +#include "cyber/service_discovery/container/multi_value_warehouse.h" #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace service_discovery { bool MultiValueWarehouse::Add(uint64_t key, const RolePtr& role, @@ -205,5 +205,5 @@ void MultiValueWarehouse::GetAllRoles(std::vector* roles_attr) { } } // namespace service_discovery -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/service_discovery/container/multi_value_warehouse.h b/cyber/service_discovery/container/multi_value_warehouse.h similarity index 83% rename from cybertron/service_discovery/container/multi_value_warehouse.h rename to cyber/service_discovery/container/multi_value_warehouse.h index 72f2be6379f..13bf5f00eed 100644 --- a/cybertron/service_discovery/container/multi_value_warehouse.h +++ b/cyber/service_discovery/container/multi_value_warehouse.h @@ -14,23 +14,23 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_SERVICE_DISCOVERY_CONTAINER_MULTI_VALUE_WAREHOUSE_H_ -#define CYBERTRON_SERVICE_DISCOVERY_CONTAINER_MULTI_VALUE_WAREHOUSE_H_ +#ifndef CYBER_SERVICE_DISCOVERY_CONTAINER_MULTI_VALUE_WAREHOUSE_H_ +#define CYBER_SERVICE_DISCOVERY_CONTAINER_MULTI_VALUE_WAREHOUSE_H_ #include #include #include -#include "cybertron/base/atomic_rw_lock.h" -#include "cybertron/service_discovery/container/warehouse_base.h" +#include "cyber/base/atomic_rw_lock.h" +#include "cyber/service_discovery/container/warehouse_base.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace service_discovery { -using apollo::cybertron::base::AtomicRWLock; -using apollo::cybertron::base::ReadLockGuard; -using apollo::cybertron::base::WriteLockGuard; +using apollo::cyber::base::AtomicRWLock; +using apollo::cyber::base::ReadLockGuard; +using apollo::cyber::base::WriteLockGuard; class MultiValueWarehouse : public WarehouseBase { public: @@ -75,7 +75,7 @@ class MultiValueWarehouse : public WarehouseBase { }; } // namespace service_discovery -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_SERVICE_DISCOVERY_CONTAINER_MULTI_VALUE_WAREHOUSE_H_ +#endif // CYBER_SERVICE_DISCOVERY_CONTAINER_MULTI_VALUE_WAREHOUSE_H_ diff --git a/cybertron/service_discovery/container/single_value_warehouse.cc b/cyber/service_discovery/container/single_value_warehouse.cc similarity index 97% rename from cybertron/service_discovery/container/single_value_warehouse.cc rename to cyber/service_discovery/container/single_value_warehouse.cc index 239d864984a..64c2d53cf67 100644 --- a/cybertron/service_discovery/container/single_value_warehouse.cc +++ b/cyber/service_discovery/container/single_value_warehouse.cc @@ -14,12 +14,12 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/service_discovery/container/single_value_warehouse.h" +#include "cyber/service_discovery/container/single_value_warehouse.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace service_discovery { bool SingleValueWarehouse::Add(uint64_t key, const RolePtr& role, @@ -198,5 +198,5 @@ void SingleValueWarehouse::GetAllRoles( } } // namespace service_discovery -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/service_discovery/container/single_value_warehouse.h b/cyber/service_discovery/container/single_value_warehouse.h similarity index 82% rename from cybertron/service_discovery/container/single_value_warehouse.h rename to cyber/service_discovery/container/single_value_warehouse.h index bdc349bde18..1743337db45 100644 --- a/cybertron/service_discovery/container/single_value_warehouse.h +++ b/cyber/service_discovery/container/single_value_warehouse.h @@ -14,23 +14,23 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_SERVICE_DISCOVERY_CONTAINER_SINGLE_VALUE_WAREHOUSE_H_ -#define CYBERTRON_SERVICE_DISCOVERY_CONTAINER_SINGLE_VALUE_WAREHOUSE_H_ +#ifndef CYBER_SERVICE_DISCOVERY_CONTAINER_SINGLE_VALUE_WAREHOUSE_H_ +#define CYBER_SERVICE_DISCOVERY_CONTAINER_SINGLE_VALUE_WAREHOUSE_H_ #include #include #include -#include "cybertron/base/atomic_rw_lock.h" -#include "cybertron/service_discovery/container/warehouse_base.h" +#include "cyber/base/atomic_rw_lock.h" +#include "cyber/service_discovery/container/warehouse_base.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace service_discovery { -using apollo::cybertron::base::AtomicRWLock; -using apollo::cybertron::base::ReadLockGuard; -using apollo::cybertron::base::WriteLockGuard; +using apollo::cyber::base::AtomicRWLock; +using apollo::cyber::base::ReadLockGuard; +using apollo::cyber::base::WriteLockGuard; class SingleValueWarehouse : public WarehouseBase { public: @@ -75,7 +75,7 @@ class SingleValueWarehouse : public WarehouseBase { }; } // namespace service_discovery -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_SERVICE_DISCOVERY_CONTAINER_SINGLE_VALUE_WAREHOUSE_H_ +#endif // CYBER_SERVICE_DISCOVERY_CONTAINER_SINGLE_VALUE_WAREHOUSE_H_ diff --git a/cybertron/service_discovery/container/warehouse_base.h b/cyber/service_discovery/container/warehouse_base.h similarity index 89% rename from cybertron/service_discovery/container/warehouse_base.h rename to cyber/service_discovery/container/warehouse_base.h index 5875f1125c5..322803f1d32 100644 --- a/cybertron/service_discovery/container/warehouse_base.h +++ b/cyber/service_discovery/container/warehouse_base.h @@ -14,16 +14,16 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_SERVICE_DISCOVERY_CONTAINER_WAREHOUSE_BASE_H_ -#define CYBERTRON_SERVICE_DISCOVERY_CONTAINER_WAREHOUSE_BASE_H_ +#ifndef CYBER_SERVICE_DISCOVERY_CONTAINER_WAREHOUSE_BASE_H_ +#define CYBER_SERVICE_DISCOVERY_CONTAINER_WAREHOUSE_BASE_H_ #include #include -#include "cybertron/service_discovery/role/role.h" +#include "cyber/service_discovery/role/role.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace service_discovery { class WarehouseBase { @@ -63,7 +63,7 @@ class WarehouseBase { }; } // namespace service_discovery -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_SERVICE_DISCOVERY_CONTAINER_WAREHOUSE_BASE_H_ +#endif // CYBER_SERVICE_DISCOVERY_CONTAINER_WAREHOUSE_BASE_H_ diff --git a/cybertron/service_discovery/container/warehouse_test.cc b/cyber/service_discovery/container/warehouse_test.cc similarity index 97% rename from cybertron/service_discovery/container/warehouse_test.cc rename to cyber/service_discovery/container/warehouse_test.cc index 51ebf945aaa..ce6a9aa6fbb 100644 --- a/cybertron/service_discovery/container/warehouse_test.cc +++ b/cyber/service_discovery/container/warehouse_test.cc @@ -16,11 +16,11 @@ #include "gtest/gtest.h" -#include "cybertron/service_discovery/container/multi_value_warehouse.h" -#include "cybertron/service_discovery/container/single_value_warehouse.h" +#include "cyber/service_discovery/container/multi_value_warehouse.h" +#include "cyber/service_discovery/container/single_value_warehouse.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace service_discovery { class WarehouseTest : public ::testing::Test { @@ -273,5 +273,5 @@ TEST_F(WarehouseTest, get_all_roles) { } } // namespace service_discovery -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/service_discovery/role/role.cc b/cyber/service_discovery/role/role.cc similarity index 94% rename from cybertron/service_discovery/role/role.cc rename to cyber/service_discovery/role/role.cc index cdbae5e507e..a5402c2e092 100644 --- a/cybertron/service_discovery/role/role.cc +++ b/cyber/service_discovery/role/role.cc @@ -14,12 +14,12 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/service_discovery/role/role.h" +#include "cyber/service_discovery/role/role.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace service_discovery { RoleBase::RoleBase() : timestamp_(0) {} @@ -89,5 +89,5 @@ bool RoleServer::Match(const RoleAttributes& target_attr) const { } } // namespace service_discovery -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/service_discovery/role/role.h b/cyber/service_discovery/role/role.h similarity index 88% rename from cybertron/service_discovery/role/role.h rename to cyber/service_discovery/role/role.h index 218278e8cef..6979fc93293 100644 --- a/cybertron/service_discovery/role/role.h +++ b/cyber/service_discovery/role/role.h @@ -14,18 +14,18 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_SERVICE_DISCOVERY_ROLE_ROLE_H_ -#define CYBERTRON_SERVICE_DISCOVERY_ROLE_ROLE_H_ +#ifndef CYBER_SERVICE_DISCOVERY_ROLE_ROLE_H_ +#define CYBER_SERVICE_DISCOVERY_ROLE_ROLE_H_ #include #include #include -#include "cybertron/common/types.h" -#include "cybertron/proto/role_attributes.pb.h" +#include "cyber/common/types.h" +#include "cyber/proto/role_attributes.pb.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace service_discovery { class RoleBase; @@ -43,7 +43,7 @@ using RoleServerPtr = std::shared_ptr; using RoleClient = RoleServer; using RoleClientPtr = std::shared_ptr; -using apollo::cybertron::proto::RoleAttributes; +using apollo::cyber::proto::RoleAttributes; class RoleBase { public: @@ -85,7 +85,7 @@ class RoleServer : public RoleBase { }; } // namespace service_discovery -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_SERVICE_DISCOVERY_ROLE_ROLE_H_ +#endif // CYBER_SERVICE_DISCOVERY_ROLE_ROLE_H_ diff --git a/cybertron/service_discovery/role/role_test.cc b/cyber/service_discovery/role/role_test.cc similarity index 97% rename from cybertron/service_discovery/role/role_test.cc rename to cyber/service_discovery/role/role_test.cc index c128ade098a..5f0600ea1ec 100644 --- a/cybertron/service_discovery/role/role_test.cc +++ b/cyber/service_discovery/role/role_test.cc @@ -16,10 +16,10 @@ #include "gtest/gtest.h" -#include "cybertron/service_discovery/role/role.h" +#include "cyber/service_discovery/role/role.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace service_discovery { TEST(RoleTest, constructor_getter_setter) { @@ -140,5 +140,5 @@ TEST(RoleTest, roleserver_match) { } } // namespace service_discovery -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/service_discovery/specific_manager/channel_manager.cc b/cyber/service_discovery/specific_manager/channel_manager.cc similarity index 96% rename from cybertron/service_discovery/specific_manager/channel_manager.cc rename to cyber/service_discovery/specific_manager/channel_manager.cc index f046cfde86c..fa5a231b5ee 100644 --- a/cybertron/service_discovery/specific_manager/channel_manager.cc +++ b/cyber/service_discovery/specific_manager/channel_manager.cc @@ -14,23 +14,23 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/service_discovery/specific_manager/channel_manager.h" +#include "cyber/service_discovery/specific_manager/channel_manager.h" #include #include #include #include -#include "cybertron/common/global_data.h" -#include "cybertron/common/log.h" -#include "cybertron/init.h" -#include "cybertron/message/message_traits.h" -#include "cybertron/message/py_message.h" -#include "cybertron/message/raw_message.h" -#include "cybertron/time/time.h" +#include "cyber/common/global_data.h" +#include "cyber/common/log.h" +#include "cyber/init.h" +#include "cyber/message/message_traits.h" +#include "cyber/message/py_message.h" +#include "cyber/message/raw_message.h" +#include "cyber/time/time.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace service_discovery { ChannelManager::ChannelManager() { @@ -314,5 +314,5 @@ void ChannelManager::DisposeLeave(const ChangeMsg& msg) { } } // namespace service_discovery -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/service_discovery/specific_manager/channel_manager.h b/cyber/service_discovery/specific_manager/channel_manager.h similarity index 83% rename from cybertron/service_discovery/specific_manager/channel_manager.h rename to cyber/service_discovery/specific_manager/channel_manager.h index 66460bf3dcd..a7933fc7318 100644 --- a/cybertron/service_discovery/specific_manager/channel_manager.h +++ b/cyber/service_discovery/specific_manager/channel_manager.h @@ -14,22 +14,22 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_SERVICE_DISCOVERY_SPECIFIC_MANAGER_CHANNEL_MANAGER_H_ -#define CYBERTRON_SERVICE_DISCOVERY_SPECIFIC_MANAGER_CHANNEL_MANAGER_H_ +#ifndef CYBER_SERVICE_DISCOVERY_SPECIFIC_MANAGER_CHANNEL_MANAGER_H_ +#define CYBER_SERVICE_DISCOVERY_SPECIFIC_MANAGER_CHANNEL_MANAGER_H_ #include #include #include #include -#include "cybertron/service_discovery/container/graph.h" -#include "cybertron/service_discovery/container/multi_value_warehouse.h" -#include "cybertron/service_discovery/container/single_value_warehouse.h" -#include "cybertron/service_discovery/role/role.h" -#include "cybertron/service_discovery/specific_manager/manager.h" +#include "cyber/service_discovery/container/graph.h" +#include "cyber/service_discovery/container/multi_value_warehouse.h" +#include "cyber/service_discovery/container/single_value_warehouse.h" +#include "cyber/service_discovery/role/role.h" +#include "cyber/service_discovery/specific_manager/manager.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace service_discovery { class TopologyManager; @@ -88,7 +88,7 @@ class ChannelManager : public Manager { }; } // namespace service_discovery -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_SERVICE_DISCOVERY_SPECIFIC_MANAGER_CHANNEL_MANAGER_H_ +#endif // CYBER_SERVICE_DISCOVERY_SPECIFIC_MANAGER_CHANNEL_MANAGER_H_ diff --git a/cybertron/service_discovery/specific_manager/channel_manager_test.cc b/cyber/service_discovery/specific_manager/channel_manager_test.cc similarity index 97% rename from cybertron/service_discovery/specific_manager/channel_manager_test.cc rename to cyber/service_discovery/specific_manager/channel_manager_test.cc index 66fefb6c69d..913d6d85afb 100644 --- a/cybertron/service_discovery/specific_manager/channel_manager_test.cc +++ b/cyber/service_discovery/specific_manager/channel_manager_test.cc @@ -19,16 +19,16 @@ #include #include -#include "cybertron/common/global_data.h" -#include "cybertron/message/message_traits.h" -#include "cybertron/message/protobuf_factory.h" -#include "cybertron/proto/chatter.pb.h" -#include "cybertron/service_discovery/specific_manager/channel_manager.h" -#include "cybertron/transport/common/identity.h" -#include "cybertron/transport/rtps/participant.h" +#include "cyber/common/global_data.h" +#include "cyber/message/message_traits.h" +#include "cyber/message/protobuf_factory.h" +#include "cyber/proto/chatter.pb.h" +#include "cyber/service_discovery/specific_manager/channel_manager.h" +#include "cyber/transport/common/identity.h" +#include "cyber/transport/rtps/participant.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace service_discovery { class ChannelManagerTest : public ::testing::Test { @@ -418,5 +418,5 @@ TEST_F(ChannelManagerTest, get_upstream_downstream) { } } // namespace service_discovery -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/service_discovery/specific_manager/manager.cc b/cyber/service_discovery/specific_manager/manager.cc similarity index 89% rename from cybertron/service_discovery/specific_manager/manager.cc rename to cyber/service_discovery/specific_manager/manager.cc index ab9f269c34a..d35cbf519b6 100644 --- a/cybertron/service_discovery/specific_manager/manager.cc +++ b/cyber/service_discovery/specific_manager/manager.cc @@ -14,19 +14,19 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/service_discovery/specific_manager/manager.h" +#include "cyber/service_discovery/specific_manager/manager.h" -#include "cybertron/common/global_data.h" -#include "cybertron/common/log.h" -#include "cybertron/message/message_traits.h" -#include "cybertron/time/time.h" -#include "cybertron/transport/qos/qos_profile_conf.h" -#include "cybertron/transport/rtps/attributes_filler.h" -#include "cybertron/transport/rtps/underlay_message.h" -#include "cybertron/transport/rtps/underlay_message_type.h" +#include "cyber/common/global_data.h" +#include "cyber/common/log.h" +#include "cyber/message/message_traits.h" +#include "cyber/time/time.h" +#include "cyber/transport/qos/qos_profile_conf.h" +#include "cyber/transport/rtps/attributes_filler.h" +#include "cyber/transport/rtps/underlay_message.h" +#include "cyber/transport/rtps/underlay_message_type.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace service_discovery { using transport::AttributesFiller; @@ -143,7 +143,7 @@ bool Manager::CreateSubscriber(RtpsParticipant* participant) { void Manager::Convert(const RoleAttributes& attr, RoleType role, OperateType opt, ChangeMsg* msg) { - msg->set_timestamp(cybertron::Time::Now().ToNanosecond()); + msg->set_timestamp(cyber::Time::Now().ToNanosecond()); msg->set_change_type(change_type_); msg->set_operate_type(opt); msg->set_role_type(role); @@ -180,7 +180,7 @@ bool Manager::Publish(const ChangeMsg& msg) { return false; } - apollo::cybertron::transport::UnderlayMessage m; + apollo::cyber::transport::UnderlayMessage m; RETURN_VAL_IF(!message::SerializeToString(msg, &m.data()), false); return publisher_->write(reinterpret_cast(&m)); } @@ -196,5 +196,5 @@ bool Manager::IsFromSameProcess(const ChangeMsg& msg) { } } // namespace service_discovery -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/service_discovery/specific_manager/manager.h b/cyber/service_discovery/specific_manager/manager.h similarity index 88% rename from cybertron/service_discovery/specific_manager/manager.h rename to cyber/service_discovery/specific_manager/manager.h index b206b292f1a..e0d4cf8a30c 100644 --- a/cybertron/service_discovery/specific_manager/manager.h +++ b/cyber/service_discovery/specific_manager/manager.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_SERVICE_DISCOVERY_SPECIFIC_MANAGER_MANAGER_H_ -#define CYBERTRON_SERVICE_DISCOVERY_SPECIFIC_MANAGER_MANAGER_H_ +#ifndef CYBER_SERVICE_DISCOVERY_SPECIFIC_MANAGER_MANAGER_H_ +#define CYBER_SERVICE_DISCOVERY_SPECIFIC_MANAGER_MANAGER_H_ #include #include @@ -29,12 +29,12 @@ #include "fastrtps/publisher/Publisher.h" #include "fastrtps/subscriber/Subscriber.h" -#include "cybertron/base/signal.h" -#include "cybertron/proto/topology_change.pb.h" -#include "cybertron/service_discovery/communication/subscriber_listener.h" +#include "cyber/base/signal.h" +#include "cyber/proto/topology_change.pb.h" +#include "cyber/service_discovery/communication/subscriber_listener.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace service_discovery { using proto::ChangeMsg; @@ -97,7 +97,7 @@ class Manager { }; } // namespace service_discovery -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_SERVICE_DISCOVERY_SPECIFIC_MANAGER_MANAGER_H_ +#endif // CYBER_SERVICE_DISCOVERY_SPECIFIC_MANAGER_MANAGER_H_ diff --git a/cybertron/service_discovery/specific_manager/node_manager.cc b/cyber/service_discovery/specific_manager/node_manager.cc similarity index 92% rename from cybertron/service_discovery/specific_manager/node_manager.cc rename to cyber/service_discovery/specific_manager/node_manager.cc index 5bab0a32d8d..36df8981d1e 100644 --- a/cybertron/service_discovery/specific_manager/node_manager.cc +++ b/cyber/service_discovery/specific_manager/node_manager.cc @@ -14,14 +14,14 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/service_discovery/specific_manager/node_manager.h" -#include "cybertron/common/global_data.h" -#include "cybertron/common/log.h" -#include "cybertron/init.h" -#include "cybertron/time/time.h" +#include "cyber/service_discovery/specific_manager/node_manager.h" +#include "cyber/common/global_data.h" +#include "cyber/common/log.h" +#include "cyber/init.h" +#include "cyber/time/time.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace service_discovery { NodeManager::NodeManager() { @@ -112,5 +112,5 @@ void NodeManager::DisposeLeave(const ChangeMsg& msg) { } } // namespace service_discovery -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/service_discovery/specific_manager/node_manager.h b/cyber/service_discovery/specific_manager/node_manager.h similarity index 77% rename from cybertron/service_discovery/specific_manager/node_manager.h rename to cyber/service_discovery/specific_manager/node_manager.h index db69070b05b..7d459a43fae 100644 --- a/cybertron/service_discovery/specific_manager/node_manager.h +++ b/cyber/service_discovery/specific_manager/node_manager.h @@ -14,19 +14,19 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_SERVICE_DISCOVERY_SPECIFIC_MANAGER_NODE_MANAGER_H_ -#define CYBERTRON_SERVICE_DISCOVERY_SPECIFIC_MANAGER_NODE_MANAGER_H_ +#ifndef CYBER_SERVICE_DISCOVERY_SPECIFIC_MANAGER_NODE_MANAGER_H_ +#define CYBER_SERVICE_DISCOVERY_SPECIFIC_MANAGER_NODE_MANAGER_H_ #include #include #include -#include "cybertron/service_discovery/container/single_value_warehouse.h" -#include "cybertron/service_discovery/role/role.h" -#include "cybertron/service_discovery/specific_manager/manager.h" +#include "cyber/service_discovery/container/single_value_warehouse.h" +#include "cyber/service_discovery/role/role.h" +#include "cyber/service_discovery/specific_manager/manager.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace service_discovery { class TopologyManager; @@ -56,7 +56,7 @@ class NodeManager : public Manager { }; } // namespace service_discovery -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_SERVICE_DISCOVERY_SPECIFIC_MANAGER_NODE_MANAGER_H_ +#endif // CYBER_SERVICE_DISCOVERY_SPECIFIC_MANAGER_NODE_MANAGER_H_ diff --git a/cybertron/service_discovery/specific_manager/node_manager_test.cc b/cyber/service_discovery/specific_manager/node_manager_test.cc similarity index 95% rename from cybertron/service_discovery/specific_manager/node_manager_test.cc rename to cyber/service_discovery/specific_manager/node_manager_test.cc index 6a06b2986d0..f97b04f6c13 100644 --- a/cybertron/service_discovery/specific_manager/node_manager_test.cc +++ b/cyber/service_discovery/specific_manager/node_manager_test.cc @@ -19,12 +19,12 @@ #include #include -#include "cybertron/common/global_data.h" -#include "cybertron/service_discovery/specific_manager/node_manager.h" -#include "cybertron/transport/rtps/participant.h" +#include "cyber/common/global_data.h" +#include "cyber/service_discovery/specific_manager/node_manager.h" +#include "cyber/transport/rtps/participant.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace service_discovery { class NodeManagerTest : public ::testing::Test { @@ -146,5 +146,5 @@ TEST_F(NodeManagerTest, get_nodes) { } } // namespace service_discovery -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/service_discovery/specific_manager/service_manager.cc b/cyber/service_discovery/specific_manager/service_manager.cc similarity index 94% rename from cybertron/service_discovery/specific_manager/service_manager.cc rename to cyber/service_discovery/specific_manager/service_manager.cc index f470beef6e9..909ca88b551 100644 --- a/cybertron/service_discovery/specific_manager/service_manager.cc +++ b/cyber/service_discovery/specific_manager/service_manager.cc @@ -14,13 +14,13 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/service_discovery/specific_manager/service_manager.h" -#include "cybertron/common/global_data.h" -#include "cybertron/common/log.h" -#include "cybertron/time/time.h" +#include "cyber/service_discovery/specific_manager/service_manager.h" +#include "cyber/common/global_data.h" +#include "cyber/common/log.h" +#include "cyber/time/time.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace service_discovery { ServiceManager::ServiceManager() { @@ -119,5 +119,5 @@ void ServiceManager::DisposeLeave(const ChangeMsg& msg) { } } // namespace service_discovery -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/service_discovery/specific_manager/service_manager.h b/cyber/service_discovery/specific_manager/service_manager.h similarity index 76% rename from cybertron/service_discovery/specific_manager/service_manager.h rename to cyber/service_discovery/specific_manager/service_manager.h index b0b97bca10f..ff45cde880e 100644 --- a/cybertron/service_discovery/specific_manager/service_manager.h +++ b/cyber/service_discovery/specific_manager/service_manager.h @@ -14,20 +14,20 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_SERVICE_DISCOVERY_SPECIFIC_MANAGER_SERVICE_MANAGER_H_ -#define CYBERTRON_SERVICE_DISCOVERY_SPECIFIC_MANAGER_SERVICE_MANAGER_H_ +#ifndef CYBER_SERVICE_DISCOVERY_SPECIFIC_MANAGER_SERVICE_MANAGER_H_ +#define CYBER_SERVICE_DISCOVERY_SPECIFIC_MANAGER_SERVICE_MANAGER_H_ #include #include #include -#include "cybertron/service_discovery/container/multi_value_warehouse.h" -#include "cybertron/service_discovery/container/single_value_warehouse.h" -#include "cybertron/service_discovery/role/role.h" -#include "cybertron/service_discovery/specific_manager/manager.h" +#include "cyber/service_discovery/container/multi_value_warehouse.h" +#include "cyber/service_discovery/container/single_value_warehouse.h" +#include "cyber/service_discovery/role/role.h" +#include "cyber/service_discovery/specific_manager/manager.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace service_discovery { class TopologyManager; @@ -60,7 +60,7 @@ class ServiceManager : public Manager { }; } // namespace service_discovery -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_SERVICE_DISCOVERY_SPECIFIC_MANAGER_SERVICE_MANAGER_H_ +#endif // CYBER_SERVICE_DISCOVERY_SPECIFIC_MANAGER_SERVICE_MANAGER_H_ diff --git a/cybertron/service_discovery/specific_manager/service_manager_test.cc b/cyber/service_discovery/specific_manager/service_manager_test.cc similarity index 95% rename from cybertron/service_discovery/specific_manager/service_manager_test.cc rename to cyber/service_discovery/specific_manager/service_manager_test.cc index bbd91dab283..edb874c4c38 100644 --- a/cybertron/service_discovery/specific_manager/service_manager_test.cc +++ b/cyber/service_discovery/specific_manager/service_manager_test.cc @@ -19,12 +19,12 @@ #include #include -#include "cybertron/common/global_data.h" -#include "cybertron/service_discovery/specific_manager/service_manager.h" -#include "cybertron/transport/rtps/participant.h" +#include "cyber/common/global_data.h" +#include "cyber/service_discovery/specific_manager/service_manager.h" +#include "cyber/transport/rtps/participant.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace service_discovery { class ServiceManagerTest : public ::testing::Test { @@ -135,5 +135,5 @@ TEST_F(ServiceManagerTest, topo_module_leave) { } } // namespace service_discovery -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/service_discovery/topology_manager.cc b/cyber/service_discovery/topology_manager.cc similarity index 95% rename from cybertron/service_discovery/topology_manager.cc rename to cyber/service_discovery/topology_manager.cc index 66d35892806..94809e28c38 100644 --- a/cybertron/service_discovery/topology_manager.cc +++ b/cyber/service_discovery/topology_manager.cc @@ -14,14 +14,14 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/service_discovery/topology_manager.h" +#include "cyber/service_discovery/topology_manager.h" -#include "cybertron/common/global_data.h" -#include "cybertron/common/log.h" -#include "cybertron/time/time.h" +#include "cyber/common/global_data.h" +#include "cyber/common/log.h" +#include "cyber/time/time.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace service_discovery { TopologyManager::TopologyManager() @@ -167,7 +167,7 @@ bool TopologyManager::Convert(const PartInfo& info, ChangeMsg* msg) { return false; } - msg->set_timestamp(cybertron::Time::Now().ToNanosecond()); + msg->set_timestamp(cyber::Time::Now().ToNanosecond()); msg->set_change_type(ChangeType::CHANGE_PARTICIPANT); msg->set_operate_type(opt_type); msg->set_role_type(RoleType::ROLE_PARTICIPANT); @@ -198,5 +198,5 @@ bool TopologyManager::ParseParticipantName(const std::string& participant_name, } } // namespace service_discovery -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/service_discovery/topology_manager.h b/cyber/service_discovery/topology_manager.h similarity index 81% rename from cybertron/service_discovery/topology_manager.h rename to cyber/service_discovery/topology_manager.h index 48d33995000..80d16d7c348 100644 --- a/cybertron/service_discovery/topology_manager.h +++ b/cyber/service_discovery/topology_manager.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_SERVICE_DISCOVERY_TOPOLOGY_H_ -#define CYBERTRON_SERVICE_DISCOVERY_TOPOLOGY_H_ +#ifndef CYBER_SERVICE_DISCOVERY_TOPOLOGY_H_ +#define CYBER_SERVICE_DISCOVERY_TOPOLOGY_H_ #include #include @@ -24,16 +24,16 @@ #include #include -#include "cybertron/base/signal.h" -#include "cybertron/common/macros.h" -#include "cybertron/service_discovery/communication/participant_listener.h" -#include "cybertron/service_discovery/specific_manager/channel_manager.h" -#include "cybertron/service_discovery/specific_manager/node_manager.h" -#include "cybertron/service_discovery/specific_manager/service_manager.h" -#include "cybertron/transport/rtps/participant.h" +#include "cyber/base/signal.h" +#include "cyber/common/macros.h" +#include "cyber/service_discovery/communication/participant_listener.h" +#include "cyber/service_discovery/specific_manager/channel_manager.h" +#include "cyber/service_discovery/specific_manager/node_manager.h" +#include "cyber/service_discovery/specific_manager/service_manager.h" +#include "cyber/transport/rtps/participant.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace service_discovery { class NodeManager; @@ -91,7 +91,7 @@ class TopologyManager { }; } // namespace service_discovery -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_SERVICE_DISCOVERY_TOPOLOGY_H_ +#endif // CYBER_SERVICE_DISCOVERY_TOPOLOGY_H_ diff --git a/cybertron/service_discovery/topology_manager_test.cc b/cyber/service_discovery/topology_manager_test.cc similarity index 93% rename from cybertron/service_discovery/topology_manager_test.cc rename to cyber/service_discovery/topology_manager_test.cc index a9c8ebb5b69..a4e01facad6 100644 --- a/cybertron/service_discovery/topology_manager_test.cc +++ b/cyber/service_discovery/topology_manager_test.cc @@ -17,11 +17,11 @@ #include #include -#include "cybertron/common/log.h" -#include "cybertron/service_discovery/topology_manager.h" +#include "cyber/common/log.h" +#include "cyber/service_discovery/topology_manager.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace service_discovery { class TopologyTest : public ::testing::Test { @@ -67,5 +67,5 @@ TEST_F(TopologyTest, get_manager) { } } // namespace service_discovery -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cyber/setup.bash b/cyber/setup.bash new file mode 100755 index 00000000000..de1ce447814 --- /dev/null +++ b/cyber/setup.bash @@ -0,0 +1,16 @@ +export CYBER_PATH=$(cd "$(dirname "${BASH_SOURCE[0]}")" && pwd) +binary_path="/apollo/bazel-bin/cyber" +tool_path="/apollo/bazel-bin/cyber/tools" +PYTHON_LD_PATH="/apollo/bazel-bin/cyber/py_wrapper" +launch_path="${CYBER_PATH}/tools/cyber_launch" +qt_path=${CYBER_PATH}/../third_party/Qt5.5.1/5.5/gcc_64 + +export LD_LIBRARY_PATH=${qt_path}/lib:$LD_LIBRARY_PATH +export QT_QPA_PLATFORM_PLUGIN_PATH=${qt_path}/plugins +export PATH=${binary_path}:${tool_path}:${launch_path}:${qt_path}/bin:$PATH +export PYTHONPATH=${PYTHON_LD_PATH}:${CYBER_PATH}/python:$PYTHONPATH + +export CYBER_DOMAIN_ID=80 +export CYBER_IP=127.0.0.1 + +source ${CYBER_PATH}/tools/cyber_tools_auto_complete.bash diff --git a/cybertron/state.cc b/cyber/state.cc similarity index 82% rename from cybertron/state.cc rename to cyber/state.cc index c2ba9ea14d9..04b36e13933 100644 --- a/cybertron/state.cc +++ b/cyber/state.cc @@ -14,19 +14,19 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/state.h" +#include "cyber/state.h" #include #include namespace apollo { -namespace cybertron { +namespace cyber { -std::atomic g_cybertron_state; +std::atomic g_cyber_state; -State GetState() { return g_cybertron_state.load(); } +State GetState() { return g_cyber_state.load(); } -void SetState(const State& state) { g_cybertron_state.store(state); } +void SetState(const State& state) { g_cyber_state.store(state); } bool OK() { return GetState() == STATE_INITIALIZED; } @@ -40,5 +40,5 @@ void WaitForShutdown() { } } -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/state.h b/cyber/state.h similarity index 89% rename from cybertron/state.h rename to cyber/state.h index 2e9dd3a3e9e..1bc018c8110 100644 --- a/cybertron/state.h +++ b/cyber/state.h @@ -14,13 +14,13 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_STATE_H_ -#define CYBERTRON_STATE_H_ +#ifndef CYBER_STATE_H_ +#define CYBER_STATE_H_ #include namespace apollo { -namespace cybertron { +namespace cyber { enum State : std::uint8_t { STATE_UNINITIALIZED = 0, @@ -36,7 +36,7 @@ bool OK(); bool IsShutdown(); void WaitForShutdown(); -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_STATE_H_ +#endif // CYBER_STATE_H_ diff --git a/cybertron/task/BUILD b/cyber/task/BUILD similarity index 85% rename from cybertron/task/BUILD rename to cyber/task/BUILD index b2c2e94dda8..5185bd37b0a 100644 --- a/cybertron/task/BUILD +++ b/cyber/task/BUILD @@ -15,7 +15,7 @@ cc_test( size = "small", srcs = [ "task_test.cc", ], deps = [ - "//cybertron:cybertron_core", + "//cyber:cyber_core", "@gtest//:main", ], ) @@ -25,7 +25,7 @@ cc_library( srcs = [ "task_manager.cc", ], hdrs = [ "task_manager.h", ], deps = [ - "//cybertron/scheduler:scheduler", + "//cyber/scheduler:scheduler", ], ) diff --git a/cybertron/task/task.h b/cyber/task/task.h similarity index 91% rename from cybertron/task/task.h rename to cyber/task/task.h index 57f95de2bfe..2aeab245890 100644 --- a/cybertron/task/task.h +++ b/cyber/task/task.h @@ -14,16 +14,16 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TASK_TASK_H_ -#define CYBERTRON_TASK_TASK_H_ +#ifndef CYBER_TASK_TASK_H_ +#define CYBER_TASK_TASK_H_ #include #include -#include "cybertron/task/task_manager.h" +#include "cyber/task/task_manager.h" namespace apollo { -namespace cybertron { +namespace cyber { template static auto Async(F&& f, Args&&... args) @@ -59,7 +59,7 @@ static inline void USleep(useconds_t usec) { } } -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TASK_TASK_H_ +#endif // CYBER_TASK_TASK_H_ diff --git a/cybertron/task/task_manager.cc b/cyber/task/task_manager.cc similarity index 87% rename from cybertron/task/task_manager.cc rename to cyber/task/task_manager.cc index 1ed14aafdff..4303f3501f8 100644 --- a/cybertron/task/task_manager.cc +++ b/cyber/task/task_manager.cc @@ -14,17 +14,17 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/task/task_manager.h" +#include "cyber/task/task_manager.h" -#include "cybertron/common/global_data.h" -#include "cybertron/croutine/croutine.h" -#include "cybertron/croutine/routine_factory.h" -#include "cybertron/scheduler/scheduler.h" +#include "cyber/common/global_data.h" +#include "cyber/croutine/croutine.h" +#include "cyber/croutine/routine_factory.h" +#include "cyber/scheduler/scheduler.h" namespace apollo { -namespace cybertron { +namespace cyber { -using apollo::cybertron::common::GlobalData; +using apollo::cyber::common::GlobalData; static const char* const task_prefix = "/internal/task"; TaskManager::TaskManager() @@ -35,7 +35,7 @@ TaskManager::TaskManager() throw std::runtime_error("Task queue init failed"); } auto func = [task_queue = this->task_queue_]() { - while (!cybertron::IsShutdown()) { + while (!cyber::IsShutdown()) { std::function task; task_queue->Dequeue(&task); if (task == nullptr) { @@ -81,5 +81,5 @@ void TaskManager::Shutdown() { } } -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/task/task_manager.h b/cyber/task/task_manager.h similarity index 88% rename from cybertron/task/task_manager.h rename to cyber/task/task_manager.h index 54e675c6281..1bbac617a0a 100644 --- a/cybertron/task/task_manager.h +++ b/cyber/task/task_manager.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TASK_TASK_MANAGER_H_ -#define CYBERTRON_TASK_TASK_MANAGER_H_ +#ifndef CYBER_TASK_TASK_MANAGER_H_ +#define CYBER_TASK_TASK_MANAGER_H_ #include #include @@ -25,11 +25,11 @@ #include #include -#include "cybertron/base/bounded_queue.h" -#include "cybertron/scheduler/scheduler.h" +#include "cyber/base/bounded_queue.h" +#include "cyber/scheduler/scheduler.h" namespace apollo { -namespace cybertron { +namespace cyber { class TaskManager { public: @@ -60,7 +60,7 @@ class TaskManager { DECLARE_SINGLETON(TaskManager); }; -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TASK_TASK_MANAGER_H_ +#endif // CYBER_TASK_TASK_MANAGER_H_ diff --git a/cybertron/task/task_test.cc b/cyber/task/task_test.cc similarity index 93% rename from cybertron/task/task_test.cc rename to cyber/task/task_test.cc index a9a49983f3f..e1e0d5f92f8 100644 --- a/cybertron/task/task_test.cc +++ b/cyber/task/task_test.cc @@ -18,12 +18,12 @@ #include #include -#include "cybertron/common/log.h" -#include "cybertron/cybertron.h" -#include "cybertron/task/task.h" +#include "cyber/common/log.h" +#include "cyber/cyber.h" +#include "cyber/task/task.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace scheduler { class Foo { @@ -95,5 +95,5 @@ TEST(AsyncTest, run_member_function) { } } // namespace scheduler -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/test/base/any_test.cc b/cyber/test/base/any_test.cc similarity index 96% rename from cybertron/test/base/any_test.cc rename to cyber/test/base/any_test.cc index b87fd1ce59f..7bc3eedec1b 100644 --- a/cybertron/test/base/any_test.cc +++ b/cyber/test/base/any_test.cc @@ -1,11 +1,11 @@ #include #include -#include "cybertron/base/any.h" +#include "cyber/base/any.h" #include "gtest/gtest.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace data { class Foo { public: @@ -106,7 +106,7 @@ TEST(AnyTest, cast_test) { } } // namespace data -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/base/atomic_hash_map_test.cc b/cyber/test/base/atomic_hash_map_test.cc similarity index 95% rename from cybertron/test/base/atomic_hash_map_test.cc rename to cyber/test/base/atomic_hash_map_test.cc index b4ca7f16e21..5929f63ca37 100644 --- a/cybertron/test/base/atomic_hash_map_test.cc +++ b/cyber/test/base/atomic_hash_map_test.cc @@ -1,10 +1,10 @@ -#include "cybertron/base/atomic_hash_map.h" +#include "cyber/base/atomic_hash_map.h" #include #include #include "gtest/gtest.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace base { TEST(AtomicHashMapTest, int_int) { @@ -74,7 +74,7 @@ TEST(AtomicHashMapTest, concurrency) { } } // namespace base -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/base/atomic_rw_lock_test.cc b/cyber/test/base/atomic_rw_lock_test.cc similarity index 94% rename from cybertron/test/base/atomic_rw_lock_test.cc rename to cyber/test/base/atomic_rw_lock_test.cc index efa2bdd9313..5baf700dd1d 100644 --- a/cybertron/test/base/atomic_rw_lock_test.cc +++ b/cyber/test/base/atomic_rw_lock_test.cc @@ -1,10 +1,10 @@ -#include "cybertron/base/atomic_rw_lock.h" +#include "cyber/base/atomic_rw_lock.h" #include -#include "cybertron/base/reentrant_rw_lock.h" +#include "cyber/base/reentrant_rw_lock.h" #include "gtest/gtest.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace base { TEST(ReentrantRWLockTest, read_lock) { @@ -94,7 +94,7 @@ TEST(ReentrantRWLockTest, write_lock) { } } // namespace base -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/base/bounded_queue_test.cc b/cyber/test/base/bounded_queue_test.cc similarity index 96% rename from cybertron/test/base/bounded_queue_test.cc rename to cyber/test/base/bounded_queue_test.cc index 850b6f04408..2a1a5c95acf 100644 --- a/cybertron/test/base/bounded_queue_test.cc +++ b/cyber/test/base/bounded_queue_test.cc @@ -1,9 +1,9 @@ -#include "cybertron/base/bounded_queue.h" +#include "cyber/base/bounded_queue.h" #include #include "gtest/gtest.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace base { TEST(BoundedQueueTest, Enqueue) { @@ -125,7 +125,7 @@ TEST(BoundedQueueTest, busy_wait) { } } // namespace base -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/base/object_pool_test.cc b/cyber/test/base/object_pool_test.cc similarity index 89% rename from cybertron/test/base/object_pool_test.cc rename to cyber/test/base/object_pool_test.cc index 0bf0579a452..be2131634f8 100644 --- a/cybertron/test/base/object_pool_test.cc +++ b/cyber/test/base/object_pool_test.cc @@ -1,9 +1,9 @@ -#include "cybertron/base/object_pool.h" +#include "cyber/base/object_pool.h" #include #include "gtest/gtest.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace base { class TestNode { @@ -30,7 +30,7 @@ TEST(ObjectPoolTest, get_object) { } } // namespace base -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/base/signal_test.cc b/cyber/test/base/signal_test.cc similarity index 97% rename from cybertron/test/base/signal_test.cc rename to cyber/test/base/signal_test.cc index 6b2e8d48525..edc77306cf6 100644 --- a/cybertron/test/base/signal_test.cc +++ b/cyber/test/base/signal_test.cc @@ -16,10 +16,10 @@ #include "gtest/gtest.h" -#include "cybertron/base/signal.h" +#include "cyber/base/signal.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace base { TEST(SlotTest, zero_input_param) { @@ -134,7 +134,7 @@ TEST(SignalTest, module) { } } // namespace base -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/blocker/blocker_manager_test.cc b/cyber/test/blocker/blocker_manager_test.cc similarity index 94% rename from cybertron/test/blocker/blocker_manager_test.cc rename to cyber/test/blocker/blocker_manager_test.cc index ca5ebc79084..4c3ee120ba6 100644 --- a/cybertron/test/blocker/blocker_manager_test.cc +++ b/cyber/test/blocker/blocker_manager_test.cc @@ -16,14 +16,14 @@ #include "gtest/gtest.h" -#include "cybertron/blocker/blocker_manager.h" -#include "cybertron/proto/unit_test.pb.h" +#include "cyber/blocker/blocker_manager.h" +#include "cyber/proto/unit_test.pb.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace blocker { -using apollo::cybertron::proto::UnitTest; +using apollo::cyber::proto::UnitTest; TEST(BlockerManagerTest, constructor) { BlockerManager blocker_manager; @@ -101,7 +101,7 @@ TEST(BlockerManagerTest, subscribe) { } } // namespace blocker -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/blocker/blocker_test.cc b/cyber/test/blocker/blocker_test.cc similarity index 95% rename from cybertron/test/blocker/blocker_test.cc rename to cyber/test/blocker/blocker_test.cc index 55e984f362b..0422608b53a 100644 --- a/cybertron/test/blocker/blocker_test.cc +++ b/cyber/test/blocker/blocker_test.cc @@ -16,14 +16,14 @@ #include "gtest/gtest.h" -#include "cybertron/blocker/blocker.h" -#include "cybertron/proto/unit_test.pb.h" +#include "cyber/blocker/blocker.h" +#include "cyber/proto/unit_test.pb.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace blocker { -using apollo::cybertron::proto::UnitTest; +using apollo::cyber::proto::UnitTest; TEST(BlockerTest, constructor) { BlockerAttr attr(10, "channel"); @@ -127,7 +127,7 @@ TEST(BlockerTest, subscribe) { } } // namespace blocker -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/class_loader/base.h b/cyber/test/class_loader/base.h similarity index 86% rename from cybertron/test/class_loader/base.h rename to cyber/test/class_loader/base.h index 43f3dcd962d..436745e0a39 100644 --- a/cybertron/test/class_loader/base.h +++ b/cyber/test/class_loader/base.h @@ -13,8 +13,8 @@ * See the License for the specific language governing permissions and * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TEST_CLASS_LOADER_BASE_H_ -#define CYBERTRON_TEST_CLASS_LOADER_BASE_H_ +#ifndef CYBER_TEST_CLASS_LOADER_BASE_H_ +#define CYBER_TEST_CLASS_LOADER_BASE_H_ class Base { public: @@ -22,4 +22,4 @@ class Base { virtual ~Base() {} }; -#endif // CYBERTRON_TEST_CLASS_LOADER_BASE_H_ +#endif // CYBER_TEST_CLASS_LOADER_BASE_H_ diff --git a/cybertron/test/class_loader/class_loader_test.cc b/cyber/test/class_loader/class_loader_test.cc similarity index 93% rename from cybertron/test/class_loader/class_loader_test.cc rename to cyber/test/class_loader/class_loader_test.cc index f65a959c146..f8b305bbb81 100644 --- a/cybertron/test/class_loader/class_loader_test.cc +++ b/cyber/test/class_loader/class_loader_test.cc @@ -20,13 +20,13 @@ #include #include -#include "cybertron/class_loader/class_loader.h" -#include "cybertron/class_loader/class_loader_manager.h" -#include "cybertron/cybertron.h" -#include "cybertron/test/class_loader/base.h" +#include "cyber/class_loader/class_loader.h" +#include "cyber/class_loader/class_loader_manager.h" +#include "cyber/cyber.h" +#include "cyber/test/class_loader/base.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace class_loader { using utility::IsLibraryLoadedByAnybody; @@ -34,9 +34,9 @@ using utility::IsLibraryLoadedByAnybody; class ClassLoaderTest : public ::testing::Test { protected: ClassLoaderTest() { - const char* cybertron_path = ::getenv("CYBERTRON_PATH"); - std::string test_path(cybertron_path); - test_path += "/test/cybertron/unit_test/"; + const char* cyber_path = ::getenv("CYBER_PATH"); + std::string test_path(cyber_path); + test_path += "/test/cyber/unit_test/"; library_1_ = test_path + "libTestPlugins1.so"; library_2_ = test_path + "libTestPlugins2.so"; } @@ -208,11 +208,11 @@ TEST_F(ClassLoaderTest, invalidBaseClass) { } } // namespace class_loader -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { - apollo::cybertron::Init(argv[0]); + apollo::cyber::Init(argv[0]); testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } diff --git a/cybertron/test/class_loader/plugins1.cc b/cyber/test/class_loader/plugins1.cc similarity index 93% rename from cybertron/test/class_loader/plugins1.cc rename to cyber/test/class_loader/plugins1.cc index 18df6113fd7..c6c32c6ca54 100644 --- a/cybertron/test/class_loader/plugins1.cc +++ b/cyber/test/class_loader/plugins1.cc @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ #include -#include "cybertron/class_loader/class_loader.h" -#include "cybertron/test/class_loader/base.h" +#include "cyber/class_loader/class_loader.h" +#include "cyber/test/class_loader/base.h" class Circle : public Base { public: diff --git a/cybertron/test/class_loader/plugins2.cc b/cyber/test/class_loader/plugins2.cc similarity index 93% rename from cybertron/test/class_loader/plugins2.cc rename to cyber/test/class_loader/plugins2.cc index 8b3b171e75b..eaa40aee2ce 100644 --- a/cybertron/test/class_loader/plugins2.cc +++ b/cyber/test/class_loader/plugins2.cc @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ #include -#include "cybertron/class_loader/class_loader.h" -#include "cybertron/test/class_loader/base.h" +#include "cyber/class_loader/class_loader.h" +#include "cyber/test/class_loader/base.h" class Apple : public Base { public: diff --git a/cybertron/test/common/environment_test.cc b/cyber/test/common/environment_test.cc similarity index 89% rename from cybertron/test/common/environment_test.cc rename to cyber/test/common/environment_test.cc index ba94c4078cc..65304d725e0 100644 --- a/cybertron/test/common/environment_test.cc +++ b/cyber/test/common/environment_test.cc @@ -18,10 +18,10 @@ #include -#include "cybertron/common/environment.h" +#include "cyber/common/environment.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace common { TEST(EnvironmentTest, get_env) { @@ -36,10 +36,10 @@ TEST(EnvironmentTest, get_env) { TEST(EnvironmentTest, work_root) { std::string before = WorkRoot(); - unsetenv("CYBERTRON_PATH"); - std::string after = GetEnv("CYBERTRON_PATH"); + unsetenv("CYBER_PATH"); + std::string after = GetEnv("CYBER_PATH"); EXPECT_EQ(after, ""); - setenv("CYBERTRON_PATH", before.c_str(), 1); + setenv("CYBER_PATH", before.c_str(), 1); after = WorkRoot(); EXPECT_EQ(after, before); } @@ -58,7 +58,7 @@ TEST(EnvironmentTest, module_root) { } } // namespace common -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/common/file_test.cc b/cyber/test/common/file_test.cc similarity index 92% rename from cybertron/test/common/file_test.cc rename to cyber/test/common/file_test.cc index cfa2b5ab692..594f6d55baf 100644 --- a/cybertron/test/common/file_test.cc +++ b/cyber/test/common/file_test.cc @@ -1,16 +1,16 @@ -#include "cybertron/common/file.h" +#include "cyber/common/file.h" #include #include -#include "cybertron/proto/unit_test.pb.h" +#include "cyber/proto/unit_test.pb.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace common { TEST(FileTest, proto_set_get_test) { - apollo::cybertron::proto::UnitTest message; + apollo::cyber::proto::UnitTest message; message.set_class_name("FileTest"); - apollo::cybertron::proto::UnitTest read_message; + apollo::cyber::proto::UnitTest read_message; EXPECT_FALSE(SetProtoToASCIIFile(message, -1)); EXPECT_FALSE(SetProtoToASCIIFile(message, "not_exists_dir/message.proto")); EXPECT_TRUE(SetProtoToASCIIFile(message, "message.ascii")); @@ -31,9 +31,9 @@ TEST(FileTest, proto_set_get_test) { } TEST(FileTest, file_utils_test) { - apollo::cybertron::proto::UnitTest message; + apollo::cyber::proto::UnitTest message; message.set_class_name("FileTest"); - apollo::cybertron::proto::UnitTest read_message; + apollo::cyber::proto::UnitTest read_message; EXPECT_TRUE(SetProtoToBinaryFile(message, "message.binary")); std::string content; @@ -94,7 +94,7 @@ TEST(FileTest, file_utils_test) { } } // namespace common -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/common/log_test.cc b/cyber/test/common/log_test.cc similarity index 81% rename from cybertron/test/common/log_test.cc rename to cyber/test/common/log_test.cc index 8f554c02af3..9be2c771de1 100644 --- a/cybertron/test/common/log_test.cc +++ b/cyber/test/common/log_test.cc @@ -1,15 +1,15 @@ -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "glog/logging.h" #include "gtest/gtest.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace common { TEST(LogTest, TestAll) { AINFO << "11111"; } } // namespace logger -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/common/logfileobject_test.cc b/cyber/test/common/logfileobject_test.cc similarity index 77% rename from cybertron/test/common/logfileobject_test.cc rename to cyber/test/common/logfileobject_test.cc index 39eab4b82c2..8bc24808ae9 100644 --- a/cybertron/test/common/logfileobject_test.cc +++ b/cyber/test/common/logfileobject_test.cc @@ -1,11 +1,11 @@ -#include "cybertron/cybertron.h" -#include "cybertron/logger/log_file_object.h" +#include "cyber/cyber.h" +#include "cyber/logger/log_file_object.h" #include "glog/logging.h" #include "gtest/gtest.h" #include "time.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace logger { TEST(LogFileObjectTest, init_and_write) { @@ -14,14 +14,14 @@ TEST(LogFileObjectTest, init_and_write) { logfileobject.SetBasename("base"); time_t timep; time(&timep); - std::string message = "cybertron logger test"; + std::string message = "cyber logger test"; logfileobject.Write(false, timep, message.c_str(), 20); logfileobject.SetExtension("unittest"); logfileobject.Flush(); } } // namespace logger -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/component/component_test.cc b/cyber/test/component/component_test.cc similarity index 80% rename from cybertron/test/component/component_test.cc rename to cyber/test/component/component_test.cc index e0dadf38a0c..f2c8a76b3ba 100644 --- a/cybertron/test/component/component_test.cc +++ b/cyber/test/component/component_test.cc @@ -16,17 +16,17 @@ #include "gtest/gtest.h" -#include "cybertron/component/component.h" -#include "cybertron/init.h" -#include "cybertron/message/raw_message.h" +#include "cyber/component/component.h" +#include "cyber/init.h" +#include "cyber/message/raw_message.h" namespace apollo { -namespace cybertron { +namespace cyber { -using apollo::cybertron::Component; -using apollo::cybertron::message::RawMessage; -using apollo::cybertron::proto::ComponentConfig; -using apollo::cybertron::proto::TimerComponentConfig; +using apollo::cyber::Component; +using apollo::cyber::message::RawMessage; +using apollo::cyber::proto::ComponentConfig; +using apollo::cyber::proto::TimerComponentConfig; static bool ret_proc = true; static bool ret_init = true; template { TEST(TimerComponent, init) { ret_proc = true; ret_init = true; - apollo::cybertron::proto::ComponentConfig compcfg; + apollo::cyber::proto::ComponentConfig compcfg; auto msg_str1 = std::make_shared(); auto msg_str2 = std::make_shared(); auto msg_str3 = std::make_shared(); auto msg_str4 = std::make_shared(); compcfg.set_name("perception"); - apollo::cybertron::proto::ReaderOption *read_opt = compcfg.add_readers(); + apollo::cyber::proto::ReaderOption *read_opt = compcfg.add_readers(); read_opt->set_channel("/perception/channel"); auto comC = std::make_shared>(); EXPECT_EQ(true, comC->Initialize(compcfg)); EXPECT_EQ(true, comC->Process(msg_str1)); compcfg.set_name("perception2"); - apollo::cybertron::proto::ReaderOption *read_opt2 = compcfg.add_readers(); + apollo::cyber::proto::ReaderOption *read_opt2 = compcfg.add_readers(); read_opt2->set_channel("/driver/channel1"); auto comB = std::make_shared>(); EXPECT_EQ(true, comB->Initialize(compcfg)); EXPECT_EQ(true, comB->Process(msg_str1, msg_str2)); compcfg.set_name("perception3"); - apollo::cybertron::proto::ReaderOption *read_opt3 = compcfg.add_readers(); + apollo::cyber::proto::ReaderOption *read_opt3 = compcfg.add_readers(); read_opt3->set_channel("/driver/channel2"); compcfg.set_name("perception4"); - apollo::cybertron::proto::ReaderOption *read_opt4 = compcfg.add_readers(); + apollo::cyber::proto::ReaderOption *read_opt4 = compcfg.add_readers(); read_opt4->set_channel("/driver/channel3"); auto comA = std::make_shared< Component_A>(); @@ -103,7 +103,7 @@ TEST(TimerComponent, init) { TEST(TimerComponentFail, init) { ret_proc = false; ret_init = false; - apollo::cybertron::proto::ComponentConfig compcfg; + apollo::cyber::proto::ComponentConfig compcfg; auto msg_str1 = std::make_shared(); auto msg_str2 = std::make_shared(); @@ -111,21 +111,21 @@ TEST(TimerComponentFail, init) { auto msg_str4 = std::make_shared(); compcfg.set_name("perception_f"); - apollo::cybertron::proto::ReaderOption *read_opt = compcfg.add_readers(); + apollo::cyber::proto::ReaderOption *read_opt = compcfg.add_readers(); read_opt->set_channel("/perception/channel"); auto comC = std::make_shared>(); EXPECT_EQ(false, comC->Initialize(compcfg)); EXPECT_EQ(false, comC->Process(msg_str1)); compcfg.set_name("perception2_f"); - apollo::cybertron::proto::ReaderOption *read_opt2 = compcfg.add_readers(); + apollo::cyber::proto::ReaderOption *read_opt2 = compcfg.add_readers(); read_opt2->set_channel("/driver/channel"); auto comB = std::make_shared>(); EXPECT_EQ(false, comB->Initialize(compcfg)); EXPECT_EQ(false, comB->Process(msg_str1, msg_str2)); compcfg.set_name("perception3_F"); - apollo::cybertron::proto::ReaderOption *read_opt3 = compcfg.add_readers(); + apollo::cyber::proto::ReaderOption *read_opt3 = compcfg.add_readers(); read_opt3->set_channel("/driver/channel"); auto comA = std::make_shared< Component_A>(); @@ -133,11 +133,11 @@ TEST(TimerComponentFail, init) { EXPECT_EQ(false, comA->Process(msg_str1, msg_str2, msg_str3, msg_str4)); } -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char **argv) { - apollo::cybertron::Init(argv[0]); + apollo::cyber::Init(argv[0]); testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } diff --git a/cybertron/test/component/timer_component_test.cc b/cyber/test/component/timer_component_test.cc similarity index 86% rename from cybertron/test/component/timer_component_test.cc rename to cyber/test/component/timer_component_test.cc index abb84e006c7..d7f36ef9d29 100644 --- a/cybertron/test/component/timer_component_test.cc +++ b/cyber/test/component/timer_component_test.cc @@ -16,11 +16,11 @@ #include "gtest/gtest.h" -#include "cybertron/component/timer_component.h" -#include "cybertron/init.h" +#include "cyber/component/timer_component.h" +#include "cyber/init.h" namespace apollo { -namespace cybertron { +namespace cyber { static bool ret_proc = true; static bool ret_init = true; @@ -35,7 +35,7 @@ class Component_Timer : public TimerComponent { TEST(TimerComponent, timertest) { ret_proc = true; ret_init = true; - apollo::cybertron::proto::TimerComponentConfig compcfg; + apollo::cyber::proto::TimerComponentConfig compcfg; compcfg.set_name("driver"); compcfg.set_interval(100); @@ -48,7 +48,7 @@ TEST(TimerComponent, timertest) { TEST(TimerComponentFalse, timerfail) { ret_proc = false; ret_init = false; - apollo::cybertron::proto::TimerComponentConfig compcfg; + apollo::cyber::proto::TimerComponentConfig compcfg; compcfg.set_name("driver1"); compcfg.set_interval(100); @@ -57,11 +57,11 @@ TEST(TimerComponentFalse, timerfail) { EXPECT_EQ(false, com->Process()); EXPECT_TRUE(com->ConfigFilePath().empty()); } -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { - apollo::cybertron::Init(argv[0]); + apollo::cyber::Init(argv[0]); testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } diff --git a/cybertron/test/croutine/croutine_test.cc b/cyber/test/croutine/croutine_test.cc similarity index 87% rename from cybertron/test/croutine/croutine_test.cc rename to cyber/test/croutine/croutine_test.cc index 573a22792d3..5ae81a12d8c 100644 --- a/cybertron/test/croutine/croutine_test.cc +++ b/cyber/test/croutine/croutine_test.cc @@ -1,12 +1,12 @@ #include -#include "cybertron/croutine/croutine.h" -#include "cybertron/croutine/routine_context.h" -#include "cybertron/cybertron.h" +#include "cyber/croutine/croutine.h" +#include "cyber/croutine/routine_context.h" +#include "cyber/cyber.h" #include "gtest/gtest.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace croutine { void Sleep(uint64_t ms) { @@ -88,14 +88,14 @@ TEST(CRoutineTest, croutine_lock) { } } // namespace croutine -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { - apollo::cybertron::Init(argv[0]); + apollo::cyber::Init(argv[0]); auto context = - std::make_shared(); - apollo::cybertron::croutine::CRoutine::SetMainContext(context); + std::make_shared(); + apollo::cyber::croutine::CRoutine::SetMainContext(context); testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } diff --git a/cybertron/test/croutine/routine_factory_test.cc b/cyber/test/croutine/routine_factory_test.cc similarity index 85% rename from cybertron/test/croutine/routine_factory_test.cc rename to cyber/test/croutine/routine_factory_test.cc index 90e856ce662..c406a8f01e7 100644 --- a/cybertron/test/croutine/routine_factory_test.cc +++ b/cyber/test/croutine/routine_factory_test.cc @@ -1,12 +1,12 @@ #include -#include "cybertron/croutine/routine_factory.h" -#include "cybertron/cybertron.h" -#include "cybertron/proto/chatter.pb.h" +#include "cyber/croutine/routine_factory.h" +#include "cyber/cyber.h" +#include "cyber/proto/chatter.pb.h" #include "gtest/gtest.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace croutine { std::hash str_hash; @@ -36,5 +36,5 @@ TEST(RoutineFactoryTest, routine_factory) { } } // namespace croutine -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/test/data/cache_buffer_test.cc b/cyber/test/data/cache_buffer_test.cc similarity index 90% rename from cybertron/test/data/cache_buffer_test.cc rename to cyber/test/data/cache_buffer_test.cc index 23cb0a480d3..d07d468409a 100644 --- a/cybertron/test/data/cache_buffer_test.cc +++ b/cyber/test/data/cache_buffer_test.cc @@ -2,10 +2,10 @@ #include #include "gtest/gtest.h" -#include "cybertron/data/cache_buffer.h" +#include "cyber/data/cache_buffer.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace data { TEST(CacheBufferTest, cache_buffer_test) { @@ -29,7 +29,7 @@ TEST(CacheBufferTest, cache_buffer_test) { } } // namespace data -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/data/channel_buffer_test.cc b/cyber/test/data/channel_buffer_test.cc similarity index 95% rename from cybertron/test/data/channel_buffer_test.cc rename to cyber/test/data/channel_buffer_test.cc index 7c74eedc188..e54f2d5c459 100644 --- a/cybertron/test/data/channel_buffer_test.cc +++ b/cyber/test/data/channel_buffer_test.cc @@ -1,11 +1,11 @@ #include "gtest/gtest.h" -#include "cybertron/common/util.h" -#include "cybertron/data/channel_buffer.h" +#include "cyber/common/util.h" +#include "cyber/data/channel_buffer.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace data { auto channel0 = common::Hash("/channel0"); @@ -81,7 +81,7 @@ TEST(ChannelBufferTest, FetchMulti) { } } // namespace data -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/data/data_dispatcher_test.cc b/cyber/test/data/data_dispatcher_test.cc similarity index 92% rename from cybertron/test/data/data_dispatcher_test.cc rename to cyber/test/data/data_dispatcher_test.cc index 703e0b36202..5cfb20790d8 100644 --- a/cybertron/test/data/data_dispatcher_test.cc +++ b/cyber/test/data/data_dispatcher_test.cc @@ -1,11 +1,11 @@ #include "gtest/gtest.h" -#include "cybertron/common/util.h" -#include "cybertron/data/data_dispatcher.h" +#include "cyber/common/util.h" +#include "cyber/data/data_dispatcher.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace data { template @@ -46,7 +46,7 @@ TEST(DataDispatcher, Dispatch) { } } // namespace data -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/data/data_visitor_test.cc b/cyber/test/data/data_visitor_test.cc similarity index 91% rename from cybertron/test/data/data_visitor_test.cc rename to cyber/test/data/data_visitor_test.cc index 5c44331faca..0c540c6bcf4 100644 --- a/cybertron/test/data/data_visitor_test.cc +++ b/cyber/test/data/data_visitor_test.cc @@ -1,17 +1,17 @@ #include "gtest/gtest.h" -#include "cybertron/common/log.h" -#include "cybertron/cybertron.h" -#include "cybertron/data/data_visitor.h" -#include "cybertron/message/raw_message.h" +#include "cyber/common/log.h" +#include "cyber/cyber.h" +#include "cyber/data/data_visitor.h" +#include "cyber/message/raw_message.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace data { -using apollo::cybertron::message::RawMessage; -using apollo::cybertron::proto::RoleAttributes; +using apollo::cyber::message::RawMessage; +using apollo::cyber::proto::RoleAttributes; std::hash str_hash; auto channel0 = str_hash("/channel0"); @@ -113,7 +113,7 @@ TEST(DataVisitorTest, four_channel) { } } // namespace data -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/logger/logger_test.cc b/cyber/test/logger/logger_test.cc similarity index 72% rename from cybertron/test/logger/logger_test.cc rename to cyber/test/logger/logger_test.cc index c79d58036fa..14ab91e89ee 100644 --- a/cybertron/test/logger/logger_test.cc +++ b/cyber/test/logger/logger_test.cc @@ -1,26 +1,26 @@ -#include "cybertron/logger/logger.h" +#include "cyber/logger/logger.h" #include "glog/logging.h" #include "gtest/gtest.h" #include "time.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace logger { TEST(LoggerTest, init_and_write) { Logger logger(google::base::GetLogger(google::INFO)); time_t timep; time(&timep); - std::string message = "cybertron logger test"; + std::string message = "cyber logger test"; logger.Write(false, timep, message.c_str(), 20); - message = "**[CybertronLoggerTest]** cybertron logger test"; + message = "**[CyberLoggerTest]** cyber logger test"; logger.Write(false, timep, message.c_str(), 20); logger.LogSize(); logger.Flush(); } } // namespace logger -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/message/message_traits_test.cc b/cyber/test/message/message_traits_test.cc similarity index 87% rename from cybertron/test/message/message_traits_test.cc rename to cyber/test/message/message_traits_test.cc index 413e3920e70..0f427813d9f 100644 --- a/cybertron/test/message/message_traits_test.cc +++ b/cyber/test/message/message_traits_test.cc @@ -16,11 +16,11 @@ #include "gtest/gtest.h" -#include "cybertron/message/message_traits.h" -#include "cybertron/proto/unit_test.pb.h" +#include "cyber/message/message_traits.h" +#include "cyber/proto/unit_test.pb.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace message { TEST(MessageTraitsTest, serialize_to_string) { @@ -43,15 +43,15 @@ TEST(MessageTraitsTest, parse_from_string) { TEST(MessageTraitsTest, message_type) { std::string msg_type = MessageType(); - EXPECT_EQ(msg_type, "apollo.cybertron.proto.UnitTest"); + EXPECT_EQ(msg_type, "apollo.cyber.proto.UnitTest"); proto::UnitTest ut; msg_type = MessageType(ut); - EXPECT_EQ(msg_type, "apollo.cybertron.proto.UnitTest"); + EXPECT_EQ(msg_type, "apollo.cyber.proto.UnitTest"); } } // namespace message -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/message/raw_message_test.cc b/cyber/test/message/raw_message_test.cc similarity index 88% rename from cybertron/test/message/raw_message_test.cc rename to cyber/test/message/raw_message_test.cc index c7a939e3739..49d79e9e45f 100644 --- a/cybertron/test/message/raw_message_test.cc +++ b/cyber/test/message/raw_message_test.cc @@ -16,10 +16,10 @@ #include "gtest/gtest.h" -#include "cybertron/message/raw_message.h" +#include "cyber/message/raw_message.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace message { TEST(RawMessageTest, constructor) { @@ -47,14 +47,14 @@ TEST(RawMessageTest, parse_from_string) { TEST(RawMessageTest, message_type) { RawMessage msg; std::string msg_type = RawMessage::TypeName(); - EXPECT_EQ(msg_type, "apollo.cybertron.message.RawMessage"); + EXPECT_EQ(msg_type, "apollo.cyber.message.RawMessage"); // msg_type = MessageType(); - // EXPECT_EQ(msg_type, "apollo.cybertron.message.RawMessage"); + // EXPECT_EQ(msg_type, "apollo.cyber.message.RawMessage"); } } // namespace message -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/node/node_test.cc b/cyber/test/node/node_test.cc similarity index 95% rename from cybertron/test/node/node_test.cc rename to cyber/test/node/node_test.cc index 2ad35f1a208..3bd9b89db61 100644 --- a/cybertron/test/node/node_test.cc +++ b/cyber/test/node/node_test.cc @@ -16,12 +16,12 @@ #include "gtest/gtest.h" -#include "cybertron/init.h" -#include "cybertron/node/node.h" -#include "cybertron/proto/unit_test.pb.h" +#include "cyber/init.h" +#include "cyber/node/node.h" +#include "cyber/proto/unit_test.pb.h" namespace apollo { -namespace cybertron { +namespace cyber { TEST(NodeTest, constructor) { Node node("constructor"); @@ -52,7 +52,7 @@ TEST(NodeTest, create_writer_with_attr) { EXPECT_TRUE(writer_a->inited()); writer_a->Shutdown(); - attr.set_message_type("apollo.cybertron.proto.UnitTest"); + attr.set_message_type("apollo.cyber.proto.UnitTest"); auto writer_b = node.CreateWriter(attr); ASSERT_TRUE(writer_b != nullptr); EXPECT_EQ(writer_b->GetChannelName(), "channel"); @@ -148,11 +148,11 @@ TEST(NodeTest, observe) { EXPECT_FALSE(reader->HasReceived()); } -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { - apollo::cybertron::Init(argv[0]); + apollo::cyber::Init(argv[0]); testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } diff --git a/cybertron/test/node/writer_reader_test.cc b/cyber/test/node/writer_reader_test.cc similarity index 96% rename from cybertron/test/node/writer_reader_test.cc rename to cyber/test/node/writer_reader_test.cc index d4f0af84f2e..be1f627b005 100644 --- a/cybertron/test/node/writer_reader_test.cc +++ b/cyber/test/node/writer_reader_test.cc @@ -18,14 +18,14 @@ #include -#include "cybertron/common/global_data.h" -#include "cybertron/init.h" -#include "cybertron/node/reader.h" -#include "cybertron/node/writer.h" -#include "cybertron/proto/unit_test.pb.h" +#include "cyber/common/global_data.h" +#include "cyber/init.h" +#include "cyber/node/reader.h" +#include "cyber/node/writer.h" +#include "cyber/proto/unit_test.pb.h" namespace apollo { -namespace cybertron { +namespace cyber { TEST(WriterReaderTest, constructor) { const std::string channel_name("constructor"); @@ -243,11 +243,11 @@ TEST(WriterReaderTest, get_delay_sec) { EXPECT_GT(reader.GetDelaySec(), 1); } -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { - apollo::cybertron::Init(argv[0]); + apollo::cyber::Init(argv[0]); testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } diff --git a/cybertron/test/other/init_cybertron_test.cc b/cyber/test/other/init_cybertron_test.cc similarity index 84% rename from cybertron/test/other/init_cybertron_test.cc rename to cyber/test/other/init_cybertron_test.cc index e8a105a9dfe..08499eb914b 100644 --- a/cybertron/test/other/init_cybertron_test.cc +++ b/cyber/test/other/init_cybertron_test.cc @@ -18,14 +18,14 @@ #include -#include "cybertron/common/log.h" -#include "cybertron/cybertron.h" -#include "cybertron/init.h" -#include "cybertron/proto/driver.pb.h" -using apollo::cybertron::proto::CarStatus; +#include "cyber/common/log.h" +#include "cyber/cyber.h" +#include "cyber/init.h" +#include "cyber/proto/driver.pb.h" +using apollo::cyber::proto::CarStatus; namespace apollo { -namespace cybertron { +namespace cyber { void VoidTask() { AINFO << "VoidTask running"; } @@ -34,12 +34,12 @@ int UserTask(const std::shared_ptr& msg) { return 0; } -TEST(InitCybertronTest, create_node) { +TEST(InitCyberTest, create_node) { auto node = CreateNode("create_node"); EXPECT_EQ(node, nullptr); } -TEST(InitCybertronTest, all_in_one) { +TEST(InitCyberTest, all_in_one) { EXPECT_FALSE(OK()); EXPECT_FALSE(IsShutdown()); @@ -65,7 +65,7 @@ TEST(InitCybertronTest, all_in_one) { Shutdown(); } -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/parameter/parameter_client_test.cc b/cyber/test/parameter/parameter_client_test.cc similarity index 87% rename from cybertron/test/parameter/parameter_client_test.cc rename to cyber/test/parameter/parameter_client_test.cc index 28888966e4e..972f3c72022 100644 --- a/cybertron/test/parameter/parameter_client_test.cc +++ b/cyber/test/parameter/parameter_client_test.cc @@ -16,16 +16,16 @@ #include "gtest/gtest.h" -#include "cybertron/cybertron.h" -#include "cybertron/message/protobuf_factory.h" -#include "cybertron/parameter/parameter_client.h" -#include "cybertron/parameter/parameter_server.h" +#include "cyber/cyber.h" +#include "cyber/message/protobuf_factory.h" +#include "cyber/parameter/parameter_client.h" +#include "cyber/parameter/parameter_server.h" namespace apollo { -namespace cybertron { +namespace cyber { -using apollo::cybertron::proto::Param; -using apollo::cybertron::proto::ParamType; +using apollo::cyber::proto::Param; +using apollo::cyber::proto::ParamType; class ParameterClientTest : public ::testing::Test { protected: @@ -85,14 +85,14 @@ TEST_F(ParameterClientTest, list_parameter) { EXPECT_FALSE(pc_->ListParameters(¶meters)); } -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { - apollo::cybertron::Init(argv[0]); + apollo::cyber::Init(argv[0]); testing::InitGoogleTest(&argc, argv); // google::InitGoogleLogging(argv[0]); auto res = RUN_ALL_TESTS(); - apollo::cybertron::Shutdown(); + apollo::cyber::Shutdown(); return res; } diff --git a/cybertron/test/parameter/parameter_server_test.cc b/cyber/test/parameter/parameter_server_test.cc similarity index 87% rename from cybertron/test/parameter/parameter_server_test.cc rename to cyber/test/parameter/parameter_server_test.cc index a5eb7c80948..9eb4a71c84d 100644 --- a/cybertron/test/parameter/parameter_server_test.cc +++ b/cyber/test/parameter/parameter_server_test.cc @@ -16,15 +16,15 @@ #include "gtest/gtest.h" -#include "cybertron/cybertron.h" -#include "cybertron/message/protobuf_factory.h" -#include "cybertron/parameter/parameter_server.h" +#include "cyber/cyber.h" +#include "cyber/message/protobuf_factory.h" +#include "cyber/parameter/parameter_server.h" namespace apollo { -namespace cybertron { +namespace cyber { -using apollo::cybertron::proto::Param; -using apollo::cybertron::proto::ParamType; +using apollo::cyber::proto::Param; +using apollo::cyber::proto::ParamType; class ParameterServerTest : public ::testing::Test { protected: @@ -68,11 +68,11 @@ TEST_F(ParameterServerTest, list_parameter) { EXPECT_EQ(1, parameters[0].AsInt64()); } -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { - apollo::cybertron::Init(argv[0]); + apollo::cyber::Init(argv[0]); testing::InitGoogleTest(&argc, argv); // google::InitGoogleLogging(argv[0]); return RUN_ALL_TESTS(); diff --git a/cybertron/test/parameter/parameter_test.cc b/cyber/test/parameter/parameter_test.cc similarity index 91% rename from cybertron/test/parameter/parameter_test.cc rename to cyber/test/parameter/parameter_test.cc index 0f0cec99e30..4e57973d79a 100644 --- a/cybertron/test/parameter/parameter_test.cc +++ b/cyber/test/parameter/parameter_test.cc @@ -16,16 +16,16 @@ #include "gtest/gtest.h" -#include "cybertron/cybertron.h" -#include "cybertron/message/message_traits.h" -#include "cybertron/parameter/parameter.h" -#include "cybertron/proto/parameter.pb.h" +#include "cyber/cyber.h" +#include "cyber/message/message_traits.h" +#include "cyber/parameter/parameter.h" +#include "cyber/proto/parameter.pb.h" namespace apollo { -namespace cybertron { +namespace cyber { -using apollo::cybertron::proto::Param; -using apollo::cybertron::proto::ParamType; +using apollo::cyber::proto::Param; +using apollo::cyber::proto::ParamType; class ParameterTest : public ::testing::Test { protected: @@ -120,7 +120,7 @@ TEST_F(ParameterTest, type_name) { EXPECT_EQ("INT", _int_param->TypeName()); EXPECT_EQ("DOUBLE", _double_param->TypeName()); EXPECT_EQ("STRING", _string_param->TypeName()); - EXPECT_EQ("apollo.cybertron.proto.Param", _protobuf_param->TypeName()); + EXPECT_EQ("apollo.cyber.proto.Param", _protobuf_param->TypeName()); } TEST_F(ParameterTest, name) { @@ -163,7 +163,7 @@ TEST_F(ParameterTest, value) { auto param = _protobuf_param->value(); EXPECT_EQ("protobuf", _protobuf_param->Name()); - EXPECT_EQ("apollo.cybertron.proto.Param", _protobuf_param->TypeName()); + EXPECT_EQ("apollo.cyber.proto.Param", _protobuf_param->TypeName()); std::string str; param.SerializeToString(&str); EXPECT_EQ(str, _protobuf_param->value()); @@ -180,16 +180,16 @@ TEST_F(ParameterTest, debug_string) { EXPECT_EQ("{name: \"string\", type: \"STRING\", value: \"test\"}", _string_param->DebugString()); EXPECT_EQ( - "{name: \"protobuf\", type: \"apollo.cybertron.proto.Param\", value: " + "{name: \"protobuf\", type: \"apollo.cyber.proto.Param\", value: " "\"name: \"param\"\"}", _protobuf_param->DebugString()); } -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { - apollo::cybertron::Init(argv[0]); + apollo::cyber::Init(argv[0]); testing::InitGoogleTest(&argc, argv); // google::InitGoogleLogging(argv[0]); return RUN_ALL_TESTS(); diff --git a/cybertron/test/record/record_file_test.cc b/cyber/test/record/record_file_test.cc similarity index 95% rename from cybertron/test/record/record_file_test.cc rename to cyber/test/record/record_file_test.cc index b91ce3a3f36..9526cacc939 100644 --- a/cybertron/test/record/record_file_test.cc +++ b/cyber/test/record/record_file_test.cc @@ -14,23 +14,23 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/record/record_file.h" -#include "cybertron/record/header_builder.h" +#include "cyber/record/record_file.h" +#include "cyber/record/header_builder.h" #include #include #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace record { const char CHAN_1[] = "/test1"; const char CHAN_2[] = "/test2"; -const char MSG_TYPE[] = "apollo.cybertron.proto.Test"; +const char MSG_TYPE[] = "apollo.cyber.proto.Test"; const char STR_10B[] = "1234567890"; const char TEST_FILE[] = "test.record"; @@ -190,13 +190,13 @@ TEST(RecordFileTest, TestOneChunkFile) { Channel chan1; chan1.set_name("/test1"); - chan1.set_message_type("apollo.cybertron.proto.Test1"); + chan1.set_message_type("apollo.cyber.proto.Test1"); chan1.set_proto_desc(""); ASSERT_TRUE(rfw->WriteChannel(chan1)); Channel chan2; chan2.set_name("/test2"); - chan2.set_message_type("apollo.cybertron.proto.Test2"); + chan2.set_message_type("apollo.cyber.proto.Test2"); chan2.set_proto_desc(""); ASSERT_TRUE(rfw->WriteChannel(chan2)); @@ -230,7 +230,7 @@ TEST(RecordFileTest, TestOneChunkFile) { } } // namespace record -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/record/record_test.cc b/cyber/test/record/record_test.cc similarity index 92% rename from cybertron/test/record/record_test.cc rename to cyber/test/record/record_test.cc index 5aa105d8044..90671c52224 100644 --- a/cybertron/test/record/record_test.cc +++ b/cyber/test/record/record_test.cc @@ -14,10 +14,10 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/record/header_builder.h" -#include "cybertron/record/record_reader.h" -#include "cybertron/record/record_viewer.h" -#include "cybertron/record/record_writer.h" +#include "cyber/record/header_builder.h" +#include "cyber/record/record_reader.h" +#include "cyber/record/record_viewer.h" +#include "cyber/record/record_writer.h" #include #include @@ -25,18 +25,18 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace record { -using apollo::cybertron::message::RawMessage; +using apollo::cyber::message::RawMessage; const char CHANNEL_NAME_1[] = "/test/channel1"; const char CHANNEL_NAME_2[] = "/test/channel2"; -const char MESSAGE_TYPE_1[] = "apollo.cybertron.proto.Test"; -const char MESSAGE_TYPE_2[] = "apollo.cybertron.proto.Channel"; +const char MESSAGE_TYPE_1[] = "apollo.cyber.proto.Test"; +const char MESSAGE_TYPE_2[] = "apollo.cyber.proto.Channel"; const char PROTO_DESC[] = "1234567890"; const char STR_10B[] = "1234567890"; const char TEST_FILE[] = "test.record"; @@ -179,5 +179,5 @@ TEST(RecordTest, TestMutiMessageFile) { } } // namespace record -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/test/record/record_viewer_test.cc b/cyber/test/record/record_viewer_test.cc similarity index 91% rename from cybertron/test/record/record_viewer_test.cc rename to cyber/test/record/record_viewer_test.cc index 2f7935b5329..f56b770f8d3 100644 --- a/cybertron/test/record/record_viewer_test.cc +++ b/cyber/test/record/record_viewer_test.cc @@ -21,21 +21,21 @@ #include #include -#include "cybertron/common/log.h" -#include "cybertron/record/record_reader.h" -#include "cybertron/record/record_viewer.h" -#include "cybertron/record/record_writer.h" +#include "cyber/common/log.h" +#include "cyber/record/record_reader.h" +#include "cyber/record/record_viewer.h" +#include "cyber/record/record_writer.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace record { -using apollo::cybertron::message::RawMessage; +using apollo::cyber::message::RawMessage; const char CHANNEL_NAME_1[] = "/test/channel1"; const char CHANNEL_NAME_2[] = "/test/channel2"; -const char MESSAGE_TYPE_1[] = "apollo.cybertron.proto.Test"; -const char MESSAGE_TYPE_2[] = "apollo.cybertron.proto.Channel"; +const char MESSAGE_TYPE_1[] = "apollo.cyber.proto.Test"; +const char MESSAGE_TYPE_2[] = "apollo.cyber.proto.Channel"; const char PROTO_DESC[] = "1234567890"; const char STR_10B[] = "1234567890"; const char TEST_FILE[] = "test.record"; @@ -150,5 +150,5 @@ TEST(RecordTest, filter_test) { } } // namespace record -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/test/scheduler/scheduler_policy_test.cc b/cyber/test/scheduler/scheduler_policy_test.cc similarity index 74% rename from cybertron/test/scheduler/scheduler_policy_test.cc rename to cyber/test/scheduler/scheduler_policy_test.cc index 1e002e8fc32..0012dd1ad1c 100644 --- a/cybertron/test/scheduler/scheduler_policy_test.cc +++ b/cyber/test/scheduler/scheduler_policy_test.cc @@ -1,12 +1,12 @@ #include "gtest/gtest.h" -#include "cybertron/common/util.h" -#include "cybertron/cybertron.h" -#include "cybertron/scheduler/policy/task_choreo.h" -#include "cybertron/scheduler/processor.h" +#include "cyber/common/util.h" +#include "cyber/cyber.h" +#include "cyber/scheduler/policy/task_choreo.h" +#include "cyber/scheduler/processor.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace scheduler { void func() {} @@ -27,11 +27,11 @@ TEST(SchedulerPolicyTest, choreo) { } } // namespace scheduler -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { - apollo::cybertron::Init(argv[0]); + apollo::cyber::Init(argv[0]); testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } diff --git a/cybertron/test/scheduler/scheduler_test.cc b/cyber/test/scheduler/scheduler_test.cc similarity index 77% rename from cybertron/test/scheduler/scheduler_test.cc rename to cyber/test/scheduler/scheduler_test.cc index 2c6c7cc66d8..87723f7c3a5 100644 --- a/cybertron/test/scheduler/scheduler_test.cc +++ b/cyber/test/scheduler/scheduler_test.cc @@ -1,10 +1,10 @@ -#include "cybertron/scheduler/scheduler.h" -#include "cybertron/croutine/routine_factory.h" -#include "cybertron/cybertron.h" +#include "cyber/scheduler/scheduler.h" +#include "cyber/croutine/routine_factory.h" +#include "cyber/cyber.h" #include "gtest/gtest.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace scheduler { auto sched = Scheduler::Instance(); @@ -29,11 +29,11 @@ TEST(SchedulerTest, remove_task) { } } // namespace scheduler -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { - apollo::cybertron::Init(argv[0]); + apollo::cyber::Init(argv[0]); testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } diff --git a/cybertron/test/service_discovery/channel_manager_test.cc b/cyber/test/service_discovery/channel_manager_test.cc similarity index 97% rename from cybertron/test/service_discovery/channel_manager_test.cc rename to cyber/test/service_discovery/channel_manager_test.cc index e8b5bd1c5cd..e9fa2258213 100644 --- a/cybertron/test/service_discovery/channel_manager_test.cc +++ b/cyber/test/service_discovery/channel_manager_test.cc @@ -16,16 +16,16 @@ #include "gtest/gtest.h" -#include "cybertron/common/global_data.h" -#include "cybertron/message/message_traits.h" -#include "cybertron/message/protobuf_factory.h" -#include "cybertron/proto/chatter.pb.h" -#include "cybertron/service_discovery/specific_manager/channel_manager.h" -#include "cybertron/transport/common/identity.h" -#include "cybertron/transport/rtps/participant.h" +#include "cyber/common/global_data.h" +#include "cyber/message/message_traits.h" +#include "cyber/message/protobuf_factory.h" +#include "cyber/proto/chatter.pb.h" +#include "cyber/service_discovery/specific_manager/channel_manager.h" +#include "cyber/transport/common/identity.h" +#include "cyber/transport/rtps/participant.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace service_discovery { class ChannelManagerTest : public ::testing::Test { @@ -432,7 +432,7 @@ TEST_F(ChannelManagerTest, get_upstream_downstream) { } } // namespace service_discovery -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/service_discovery/graph_test.cc b/cyber/test/service_discovery/graph_test.cc similarity index 98% rename from cybertron/test/service_discovery/graph_test.cc rename to cyber/test/service_discovery/graph_test.cc index 1f0aa253613..ddd00bbab36 100644 --- a/cybertron/test/service_discovery/graph_test.cc +++ b/cyber/test/service_discovery/graph_test.cc @@ -16,10 +16,10 @@ #include "gtest/gtest.h" -#include "cybertron/service_discovery/container/graph.h" +#include "cyber/service_discovery/container/graph.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace service_discovery { TEST(GraphTest, vertice) { @@ -205,7 +205,7 @@ TEST(GraphTest, graph) { } } // namespace service_discovery -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/service_discovery/node_manager_test.cc b/cyber/test/service_discovery/node_manager_test.cc similarity index 96% rename from cybertron/test/service_discovery/node_manager_test.cc rename to cyber/test/service_discovery/node_manager_test.cc index fb6615eef51..4813ca049dc 100644 --- a/cybertron/test/service_discovery/node_manager_test.cc +++ b/cyber/test/service_discovery/node_manager_test.cc @@ -16,12 +16,12 @@ #include "gtest/gtest.h" -#include "cybertron/common/global_data.h" -#include "cybertron/service_discovery/specific_manager/node_manager.h" -#include "cybertron/transport/rtps/participant.h" +#include "cyber/common/global_data.h" +#include "cyber/service_discovery/specific_manager/node_manager.h" +#include "cyber/transport/rtps/participant.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace service_discovery { class NodeManagerTest : public ::testing::Test { @@ -148,7 +148,7 @@ TEST_F(NodeManagerTest, get_nodes) { } } // namespace service_discovery -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/service_discovery/role_test.cc b/cyber/test/service_discovery/role_test.cc similarity index 97% rename from cybertron/test/service_discovery/role_test.cc rename to cyber/test/service_discovery/role_test.cc index 2dd28a4a1d2..4bf9c863e36 100644 --- a/cybertron/test/service_discovery/role_test.cc +++ b/cyber/test/service_discovery/role_test.cc @@ -16,10 +16,10 @@ #include "gtest/gtest.h" -#include "cybertron/service_discovery/role/role.h" +#include "cyber/service_discovery/role/role.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace service_discovery { TEST(RoleTest, constructor_getter_setter) { @@ -140,7 +140,7 @@ TEST(RoleTest, roleserver_match) { } } // namespace service_discovery -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/service_discovery/service_manager_test.cc b/cyber/test/service_discovery/service_manager_test.cc similarity index 96% rename from cybertron/test/service_discovery/service_manager_test.cc rename to cyber/test/service_discovery/service_manager_test.cc index 5bfea0219a1..a2531210234 100644 --- a/cybertron/test/service_discovery/service_manager_test.cc +++ b/cyber/test/service_discovery/service_manager_test.cc @@ -16,12 +16,12 @@ #include "gtest/gtest.h" -#include "cybertron/common/global_data.h" -#include "cybertron/service_discovery/specific_manager/service_manager.h" -#include "cybertron/transport/rtps/participant.h" +#include "cyber/common/global_data.h" +#include "cyber/service_discovery/specific_manager/service_manager.h" +#include "cyber/transport/rtps/participant.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace service_discovery { class ServiceManagerTest : public ::testing::Test { @@ -136,7 +136,7 @@ TEST_F(ServiceManagerTest, topo_module_leave) { } } // namespace service_discovery -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/service_discovery/topology_manager_test.cc b/cyber/test/service_discovery/topology_manager_test.cc similarity index 94% rename from cybertron/test/service_discovery/topology_manager_test.cc rename to cyber/test/service_discovery/topology_manager_test.cc index 96ebf9c628d..8c0ddc0fe00 100644 --- a/cybertron/test/service_discovery/topology_manager_test.cc +++ b/cyber/test/service_discovery/topology_manager_test.cc @@ -16,11 +16,11 @@ #include "gtest/gtest.h" -#include "cybertron/common/log.h" -#include "cybertron/service_discovery/topology_manager.h" +#include "cyber/common/log.h" +#include "cyber/service_discovery/topology_manager.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace service_discovery { class TopologyTest : public ::testing::Test { @@ -71,7 +71,7 @@ TEST_F(TopologyTest, get_manager) { } } // namespace service_discovery -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/service_discovery/warehouse_test.cc b/cyber/test/service_discovery/warehouse_test.cc similarity index 97% rename from cybertron/test/service_discovery/warehouse_test.cc rename to cyber/test/service_discovery/warehouse_test.cc index edfbc2d4e5d..260bfb625b8 100644 --- a/cybertron/test/service_discovery/warehouse_test.cc +++ b/cyber/test/service_discovery/warehouse_test.cc @@ -16,11 +16,11 @@ #include "gtest/gtest.h" -#include "cybertron/service_discovery/container/multi_value_warehouse.h" -#include "cybertron/service_discovery/container/single_value_warehouse.h" +#include "cyber/service_discovery/container/multi_value_warehouse.h" +#include "cyber/service_discovery/container/single_value_warehouse.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace service_discovery { class WarehouseTest : public ::testing::Test { @@ -273,7 +273,7 @@ TEST_F(WarehouseTest, get_all_roles) { } } // namespace service_discovery -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/task/task_test.cc b/cyber/test/task/task_test.cc similarity index 89% rename from cybertron/test/task/task_test.cc rename to cyber/test/task/task_test.cc index b0d01f06a33..d0f5d2be7be 100644 --- a/cybertron/test/task/task_test.cc +++ b/cyber/test/task/task_test.cc @@ -1,10 +1,10 @@ -#include "cybertron/task/task.h" -#include "cybertron/common/log.h" -#include "cybertron/cybertron.h" +#include "cyber/task/task.h" +#include "cyber/common/log.h" +#include "cyber/cyber.h" #include "gtest/gtest.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace scheduler { class Foo { @@ -76,11 +76,11 @@ TEST(AsyncTest, run_member_function) { } } // namespace scheduler -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { - apollo::cybertron::Init(argv[0]); + apollo::cyber::Init(argv[0]); testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } diff --git a/cybertron/test/time/duration_test.cc b/cyber/test/time/duration_test.cc similarity index 91% rename from cybertron/test/time/duration_test.cc rename to cyber/test/time/duration_test.cc index cee44a0eab6..80965d13c66 100644 --- a/cybertron/test/time/duration_test.cc +++ b/cyber/test/time/duration_test.cc @@ -1,10 +1,10 @@ -#include "cybertron/time/duration.h" +#include "cyber/time/duration.h" #include -#include "cybertron/time/time.h" +#include "cyber/time/time.h" #include "gtest/gtest.h" namespace apollo { -namespace cybertron { +namespace cyber { TEST(DurationTest, constructor) { Duration duration(100); @@ -48,7 +48,7 @@ TEST(DurationTest, is_zero) { EXPECT_TRUE(duration.IsZero()); } -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/time/time_test.cc b/cyber/test/time/time_test.cc similarity index 91% rename from cybertron/test/time/time_test.cc rename to cyber/test/time/time_test.cc index 9fda1db7216..6706c5660f4 100644 --- a/cybertron/test/time/time_test.cc +++ b/cyber/test/time/time_test.cc @@ -1,10 +1,10 @@ -#include "cybertron/time/time.h" +#include "cyber/time/time.h" #include -#include "cybertron/time/duration.h" +#include "cyber/time/duration.h" #include "gtest/gtest.h" namespace apollo { -namespace cybertron { +namespace cyber { TEST(TimeTest, constructor) { Time time(100UL); @@ -53,7 +53,7 @@ TEST(TimeTest, is_zero) { EXPECT_FALSE(Time::MIN.IsZero()); } -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/timer/timer_manager_test.cc b/cyber/test/timer/timer_manager_test.cc similarity index 91% rename from cybertron/test/timer/timer_manager_test.cc rename to cyber/test/timer/timer_manager_test.cc index 88683baea05..acee6dbef27 100644 --- a/cybertron/test/timer/timer_manager_test.cc +++ b/cyber/test/timer/timer_manager_test.cc @@ -14,14 +14,14 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/timer/timer_manager.h" +#include "cyber/timer/timer_manager.h" #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { -namespace cybertron { +namespace cyber { TEST(TimerManagerTest, Basic) { std::shared_ptr tm_ = TimerManager::Instance(); @@ -32,7 +32,7 @@ TEST(TimerManagerTest, Basic) { ASSERT_EQ(tm_->IsRunning(), false); } -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/timer/timing_wheel_test.cc b/cyber/test/timer/timing_wheel_test.cc similarity index 94% rename from cybertron/test/timer/timing_wheel_test.cc rename to cyber/test/timer/timing_wheel_test.cc index dbb915e982f..7b0e73eacd1 100644 --- a/cybertron/test/timer/timing_wheel_test.cc +++ b/cyber/test/timer/timing_wheel_test.cc @@ -14,16 +14,16 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/timer/timing_wheel.h" +#include "cyber/timer/timing_wheel.h" #include #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { -namespace cybertron { +namespace cyber { class TestHandler { public: @@ -68,7 +68,7 @@ TEST(TimingWheelTest, Period) { } } -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/tools/recorder_test.cc b/cyber/test/tools/recorder_test.cc similarity index 84% rename from cybertron/test/tools/recorder_test.cc rename to cyber/test/tools/recorder_test.cc index 0ead5c52e0e..78a64717050 100644 --- a/cybertron/test/tools/recorder_test.cc +++ b/cyber/test/tools/recorder_test.cc @@ -4,9 +4,9 @@ #include "gtest/gtest.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport {} // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/transport/common_test.cc b/cyber/test/transport/common_test.cc similarity index 90% rename from cybertron/test/transport/common_test.cc rename to cyber/test/transport/common_test.cc index d1b2bc24cd1..0c9602c8bda 100644 --- a/cybertron/test/transport/common_test.cc +++ b/cyber/test/transport/common_test.cc @@ -3,13 +3,13 @@ #include "gtest/gtest.h" -#include "cybertron/common/global_data.h" -#include "cybertron/transport/common/endpoint.h" -#include "cybertron/transport/common/identity.h" -#include "cybertron/transport/common/syscall_wrapper.h" +#include "cyber/common/global_data.h" +#include "cyber/transport/common/endpoint.h" +#include "cyber/transport/common/identity.h" +#include "cyber/transport/common/syscall_wrapper.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { TEST(IdentityTest, identity_test) { @@ -82,7 +82,7 @@ TEST(SyscallWrapperTest, syscall_wrapper_test) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/transport/dispatcher_test.cc b/cyber/test/transport/dispatcher_test.cc similarity index 95% rename from cybertron/test/transport/dispatcher_test.cc rename to cyber/test/transport/dispatcher_test.cc index fd8eb4d2ffb..e4b2cf13a24 100644 --- a/cybertron/test/transport/dispatcher_test.cc +++ b/cyber/test/transport/dispatcher_test.cc @@ -16,13 +16,13 @@ #include "gtest/gtest.h" -#include "cybertron/common/util.h" -#include "cybertron/proto/chatter.pb.h" -#include "cybertron/transport/common/identity.h" -#include "cybertron/transport/dispatcher/dispatcher.h" +#include "cyber/common/util.h" +#include "cyber/proto/chatter.pb.h" +#include "cyber/transport/common/identity.h" +#include "cyber/transport/dispatcher/dispatcher.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { class DispatcherTest : public ::testing::Test { @@ -128,7 +128,7 @@ TEST_F(DispatcherTest, has_channel) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/transport/hybrid_transceiver_test.cc b/cyber/test/transport/hybrid_transceiver_test.cc similarity index 96% rename from cybertron/test/transport/hybrid_transceiver_test.cc rename to cyber/test/transport/hybrid_transceiver_test.cc index 92835ce4140..a2a21c98b90 100644 --- a/cybertron/test/transport/hybrid_transceiver_test.cc +++ b/cyber/test/transport/hybrid_transceiver_test.cc @@ -18,16 +18,16 @@ #include -#include "cybertron/common/global_data.h" -#include "cybertron/common/util.h" -#include "cybertron/proto/unit_test.pb.h" -#include "cybertron/transport/qos/qos_profile_conf.h" -#include "cybertron/transport/receiver/hybrid_receiver.h" -#include "cybertron/transport/transmitter/hybrid_transmitter.h" -#include "cybertron/transport/transport.h" +#include "cyber/common/global_data.h" +#include "cyber/common/util.h" +#include "cyber/proto/unit_test.pb.h" +#include "cyber/transport/qos/qos_profile_conf.h" +#include "cyber/transport/receiver/hybrid_receiver.h" +#include "cyber/transport/transmitter/hybrid_transmitter.h" +#include "cyber/transport/transport.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { class HybridTransceiverTest : public ::testing::Test { @@ -393,12 +393,12 @@ TEST_F(HybridTransceiverTest, enable_and_disable_with_param_diff_host) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { testing::InitGoogleTest(&argc, argv); auto res = RUN_ALL_TESTS(); - apollo::cybertron::transport::Transport::Shutdown(); + apollo::cyber::transport::Transport::Shutdown(); return res; } diff --git a/cybertron/test/transport/intra_dispatcher_test.cc b/cyber/test/transport/intra_dispatcher_test.cc similarity index 91% rename from cybertron/test/transport/intra_dispatcher_test.cc rename to cyber/test/transport/intra_dispatcher_test.cc index 3616a6e80a4..46128e5b1ee 100644 --- a/cybertron/test/transport/intra_dispatcher_test.cc +++ b/cyber/test/transport/intra_dispatcher_test.cc @@ -16,14 +16,14 @@ #include "gtest/gtest.h" -#include "cybertron/common/util.h" -#include "cybertron/message/raw_message.h" -#include "cybertron/proto/chatter.pb.h" -#include "cybertron/transport/common/identity.h" -#include "cybertron/transport/dispatcher/intra_dispatcher.h" +#include "cyber/common/util.h" +#include "cyber/message/raw_message.h" +#include "cyber/proto/chatter.pb.h" +#include "cyber/transport/common/identity.h" +#include "cyber/transport/dispatcher/intra_dispatcher.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { TEST(IntraDispatcherTest, constructor) { @@ -81,7 +81,7 @@ TEST(IntraDispatcherTest, on_message) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/transport/intra_transceiver_test.cc b/cyber/test/transport/intra_transceiver_test.cc similarity index 95% rename from cybertron/test/transport/intra_transceiver_test.cc rename to cyber/test/transport/intra_transceiver_test.cc index fc7b73e16d3..cd4266385ee 100644 --- a/cybertron/test/transport/intra_transceiver_test.cc +++ b/cyber/test/transport/intra_transceiver_test.cc @@ -16,12 +16,12 @@ #include "gtest/gtest.h" -#include "cybertron/proto/unit_test.pb.h" -#include "cybertron/transport/receiver/intra_receiver.h" -#include "cybertron/transport/transmitter/intra_transmitter.h" +#include "cyber/proto/unit_test.pb.h" +#include "cyber/transport/receiver/intra_receiver.h" +#include "cyber/transport/transmitter/intra_transmitter.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { class IntraTranceiverTest : public ::testing::Test { @@ -133,7 +133,7 @@ TEST_F(IntraTranceiverTest, enable_and_disable) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/transport/message_test.cc b/cyber/test/transport/message_test.cc similarity index 91% rename from cybertron/test/transport/message_test.cc rename to cyber/test/transport/message_test.cc index 3898403beec..72cc5bdb568 100644 --- a/cybertron/test/transport/message_test.cc +++ b/cyber/test/transport/message_test.cc @@ -1,17 +1,17 @@ #include "gtest/gtest.h" -#include "cybertron/common/global_data.h" -#include "cybertron/message/raw_message.h" -#include "cybertron/transport/message/history.h" -#include "cybertron/transport/message/history_attributes.h" -#include "cybertron/transport/message/listener_handler.h" -#include "cybertron/transport/message/message_info.h" +#include "cyber/common/global_data.h" +#include "cyber/message/raw_message.h" +#include "cyber/transport/message/history.h" +#include "cyber/transport/message/history_attributes.h" +#include "cyber/transport/message/listener_handler.h" +#include "cyber/transport/message/message_info.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { -using apollo::cybertron::message::RawMessage; +using apollo::cyber::message::RawMessage; TEST(MessageInfoTest, message_info_test) { Identity sender_id; @@ -146,7 +146,7 @@ TEST(ListenerHandlerTest, listener_handler_test) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/transport/reactor_test.cc b/cyber/test/transport/reactor_test.cc similarity index 94% rename from cybertron/test/transport/reactor_test.cc rename to cyber/test/transport/reactor_test.cc index 982da32c3c6..ad265a9083c 100644 --- a/cybertron/test/transport/reactor_test.cc +++ b/cyber/test/transport/reactor_test.cc @@ -20,12 +20,12 @@ #include #include -#include "cybertron/common/log.h" -#include "cybertron/transport/common/syscall_wrapper.h" -#include "cybertron/transport/reactor/reactor.h" +#include "cyber/common/log.h" +#include "cyber/transport/common/syscall_wrapper.h" +#include "cyber/transport/reactor/reactor.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { TEST(ReactorTest, constructor) { @@ -113,7 +113,7 @@ TEST(ReactorTest, shutdown) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/transport/rtps_dispatcher_test.cc b/cyber/test/transport/rtps_dispatcher_test.cc similarity index 91% rename from cybertron/test/transport/rtps_dispatcher_test.cc rename to cyber/test/transport/rtps_dispatcher_test.cc index 322c7ab98af..6f4da5eb7aa 100644 --- a/cybertron/test/transport/rtps_dispatcher_test.cc +++ b/cyber/test/transport/rtps_dispatcher_test.cc @@ -16,15 +16,15 @@ #include "gtest/gtest.h" -#include "cybertron/common/util.h" -#include "cybertron/proto/chatter.pb.h" -#include "cybertron/transport/common/identity.h" -#include "cybertron/transport/dispatcher/rtps_dispatcher.h" -#include "cybertron/transport/qos/qos_profile_conf.h" -#include "cybertron/transport/transport.h" +#include "cyber/common/util.h" +#include "cyber/proto/chatter.pb.h" +#include "cyber/transport/common/identity.h" +#include "cyber/transport/dispatcher/rtps_dispatcher.h" +#include "cyber/transport/qos/qos_profile_conf.h" +#include "cyber/transport/transport.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { TEST(RtpsDispatcherTest, constructor) { @@ -102,7 +102,7 @@ TEST(RtpsDispatcherTest, shutdown) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/transport/rtps_test.cc b/cyber/test/transport/rtps_test.cc similarity index 95% rename from cybertron/test/transport/rtps_test.cc rename to cyber/test/transport/rtps_test.cc index 1598777870f..fc4163ae3e1 100644 --- a/cybertron/test/transport/rtps_test.cc +++ b/cyber/test/transport/rtps_test.cc @@ -2,16 +2,16 @@ #include #include -#include "cybertron/common/global_data.h" -#include "cybertron/common/log.h" -#include "cybertron/transport/qos/qos_profile_conf.h" -#include "cybertron/transport/rtps/attributes_filler.h" -#include "cybertron/transport/rtps/participant.h" -#include "cybertron/transport/rtps/underlay_message.h" -#include "cybertron/transport/rtps/underlay_message_type.h" +#include "cyber/common/global_data.h" +#include "cyber/common/log.h" +#include "cyber/transport/qos/qos_profile_conf.h" +#include "cyber/transport/rtps/attributes_filler.h" +#include "cyber/transport/rtps/participant.h" +#include "cyber/transport/rtps/underlay_message.h" +#include "cyber/transport/rtps/underlay_message_type.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { TEST(AttributesFillerTest, fill_in_pub_attr_test) { @@ -211,7 +211,7 @@ TEST(UnderlayMessageTest, underlay_message_test) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/transport/rtps_transceiver_test.cc b/cyber/test/transport/rtps_transceiver_test.cc similarity index 94% rename from cybertron/test/transport/rtps_transceiver_test.cc rename to cyber/test/transport/rtps_transceiver_test.cc index bb37aaa3d56..ad1a8a367c2 100644 --- a/cybertron/test/transport/rtps_transceiver_test.cc +++ b/cyber/test/transport/rtps_transceiver_test.cc @@ -18,14 +18,14 @@ #include -#include "cybertron/common/util.h" -#include "cybertron/proto/unit_test.pb.h" -#include "cybertron/transport/receiver/rtps_receiver.h" -#include "cybertron/transport/transmitter/rtps_transmitter.h" -#include "cybertron/transport/transport.h" +#include "cyber/common/util.h" +#include "cyber/proto/unit_test.pb.h" +#include "cyber/transport/receiver/rtps_receiver.h" +#include "cyber/transport/transmitter/rtps_transmitter.h" +#include "cyber/transport/transport.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { class RtpsTransceiverTest : public ::testing::Test { @@ -147,7 +147,7 @@ TEST_F(RtpsTransceiverTest, enable_and_disable) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/transport/shm_dispatcher_test.cc b/cyber/test/transport/shm_dispatcher_test.cc similarity index 89% rename from cybertron/test/transport/shm_dispatcher_test.cc rename to cyber/test/transport/shm_dispatcher_test.cc index 1eef5acd2b7..48cefac806f 100644 --- a/cybertron/test/transport/shm_dispatcher_test.cc +++ b/cyber/test/transport/shm_dispatcher_test.cc @@ -16,17 +16,17 @@ #include "gtest/gtest.h" -#include "cybertron/common/global_data.h" -#include "cybertron/common/log.h" -#include "cybertron/common/util.h" -#include "cybertron/message/raw_message.h" -#include "cybertron/proto/chatter.pb.h" -#include "cybertron/transport/common/identity.h" -#include "cybertron/transport/dispatcher/shm_dispatcher.h" -#include "cybertron/transport/transport.h" +#include "cyber/common/global_data.h" +#include "cyber/common/log.h" +#include "cyber/common/util.h" +#include "cyber/message/raw_message.h" +#include "cyber/proto/chatter.pb.h" +#include "cyber/transport/common/identity.h" +#include "cyber/transport/dispatcher/shm_dispatcher.h" +#include "cyber/transport/transport.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { TEST(ShmDispatcherTest, constructor) { @@ -104,7 +104,7 @@ TEST(ShmDispatcherTest, shutdown) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/transport/shm_test.cc b/cyber/test/transport/shm_test.cc similarity index 91% rename from cybertron/test/transport/shm_test.cc rename to cyber/test/transport/shm_test.cc index 36f60b87961..916ccfa6dfb 100644 --- a/cybertron/test/transport/shm_test.cc +++ b/cyber/test/transport/shm_test.cc @@ -1,25 +1,25 @@ #include "gtest/gtest.h" //#include -#include "cybertron/common/log.h" -#include "cybertron/common/util.h" -#include "cybertron/message/raw_message.h" -#include "cybertron/transport/common/identity.h" -#include "cybertron/transport/message/message_info.h" -#include "cybertron/transport/shm/block.h" -#include "cybertron/transport/shm/readable_info.h" -#include "cybertron/transport/shm/segment.h" -#include "cybertron/transport/shm/segment.h" -#include "cybertron/transport/shm/shm_conf.h" -#include "cybertron/transport/shm/state.h" +#include "cyber/common/log.h" +#include "cyber/common/util.h" +#include "cyber/message/raw_message.h" +#include "cyber/transport/common/identity.h" +#include "cyber/transport/message/message_info.h" +#include "cyber/transport/shm/block.h" +#include "cyber/transport/shm/readable_info.h" +#include "cyber/transport/shm/segment.h" +#include "cyber/transport/shm/segment.h" +#include "cyber/transport/shm/shm_conf.h" +#include "cyber/transport/shm/state.h" #include "transport_mocker.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { // shmget shmat shmctl shmdt -using cybertron::message::RawMessage; +using cyber::message::RawMessage; TEST(BlockTest, read_write_test) { Block block; @@ -193,7 +193,7 @@ TEST(SegmentTest, segment_read_write_test) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/transport/shm_transceiver_test.cc b/cyber/test/transport/shm_transceiver_test.cc similarity index 94% rename from cybertron/test/transport/shm_transceiver_test.cc rename to cyber/test/transport/shm_transceiver_test.cc index 01c73e9b489..9b9a1c87e8d 100644 --- a/cybertron/test/transport/shm_transceiver_test.cc +++ b/cyber/test/transport/shm_transceiver_test.cc @@ -18,14 +18,14 @@ #include -#include "cybertron/common/global_data.h" -#include "cybertron/common/util.h" -#include "cybertron/proto/unit_test.pb.h" -#include "cybertron/transport/receiver/shm_receiver.h" -#include "cybertron/transport/transmitter/shm_transmitter.h" +#include "cyber/common/global_data.h" +#include "cyber/common/util.h" +#include "cyber/proto/unit_test.pb.h" +#include "cyber/transport/receiver/shm_receiver.h" +#include "cyber/transport/transmitter/shm_transmitter.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { class ShmTransceiverTest : public ::testing::Test { @@ -146,7 +146,7 @@ TEST_F(ShmTransceiverTest, enable_and_disable) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/test/transport/transport_mocker.h b/cyber/test/transport/transport_mocker.h similarity index 97% rename from cybertron/test/transport/transport_mocker.h rename to cyber/test/transport/transport_mocker.h index 9819001f570..e5278ce2aa0 100644 --- a/cybertron/test/transport/transport_mocker.h +++ b/cyber/test/transport/transport_mocker.h @@ -2,7 +2,7 @@ #include namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { /* class TransportMock { @@ -63,5 +63,5 @@ int shmdt(int shmid, int cmd, struct shmid_ds *buf) { }*/ } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo \ No newline at end of file diff --git a/cybertron/test/transport/transport_test.cc b/cyber/test/transport/transport_test.cc similarity index 94% rename from cybertron/test/transport/transport_test.cc rename to cyber/test/transport/transport_test.cc index a60987279ba..c4182f18882 100644 --- a/cybertron/test/transport/transport_test.cc +++ b/cyber/test/transport/transport_test.cc @@ -18,12 +18,12 @@ #include -#include "cybertron/proto/unit_test.pb.h" -#include "cybertron/transport/common/identity.h" -#include "cybertron/transport/transport.h" +#include "cyber/proto/unit_test.pb.h" +#include "cyber/transport/common/identity.h" +#include "cyber/transport/transport.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { using TransmitterPtr = std::shared_ptr>; @@ -89,7 +89,7 @@ TEST(TransportTest, create_receiver) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { diff --git a/cybertron/time/BUILD b/cyber/time/BUILD similarity index 82% rename from cybertron/time/BUILD rename to cyber/time/BUILD index d17cece74db..04f06f48f9d 100644 --- a/cybertron/time/BUILD +++ b/cyber/time/BUILD @@ -12,7 +12,7 @@ cc_library( ], deps = [ "duration", - "//cybertron/common:common", + "//cyber/common:common", ], ) @@ -23,7 +23,7 @@ cc_test( "time_test.cc", ], deps = [ - "//cybertron:cybertron_core", + "//cyber:cyber_core", "@gtest//:main", ], ) @@ -39,7 +39,7 @@ cc_library( deps = [ "time", "duration", - "//cybertron/common:common", + "//cyber/common:common", ], ) @@ -52,7 +52,7 @@ cc_library( "duration.h", ], deps = [ - "//cybertron/common:common", + "//cyber/common:common", ], ) @@ -63,7 +63,7 @@ cc_test( "duration_test.cc", ], deps = [ - "//cybertron:cybertron_core", + "//cyber:cyber_core", "@gtest//:main", ], ) diff --git a/cybertron/time/duration.cc b/cyber/time/duration.cc similarity index 97% rename from cybertron/time/duration.cc rename to cyber/time/duration.cc index f02e6e0f966..40567e9a2ab 100644 --- a/cybertron/time/duration.cc +++ b/cyber/time/duration.cc @@ -14,14 +14,14 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/time/duration.h" +#include "cyber/time/duration.h" #include #include #include #include namespace apollo { -namespace cybertron { +namespace cyber { Duration::Duration(int64_t nanoseconds) { nanoseconds_ = nanoseconds; } @@ -117,5 +117,5 @@ std::ostream &operator<<(std::ostream &os, const Duration &rhs) { return os; } -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/time/duration.h b/cyber/time/duration.h similarity index 92% rename from cybertron/time/duration.h rename to cyber/time/duration.h index a60ef8ff7d5..f0df3a2940a 100644 --- a/cybertron/time/duration.h +++ b/cyber/time/duration.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TIME_DURATION_H_ -#define CYBERTRON_TIME_DURATION_H_ +#ifndef CYBER_TIME_DURATION_H_ +#define CYBER_TIME_DURATION_H_ #include #include @@ -24,7 +24,7 @@ #include namespace apollo { -namespace cybertron { +namespace cyber { class Duration { public: @@ -62,7 +62,7 @@ class Duration { std::ostream &operator<<(std::ostream &os, const Duration &rhs); -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TIME_DURATION_H_ +#endif // CYBER_TIME_DURATION_H_ diff --git a/cybertron/time/duration_test.cc b/cyber/time/duration_test.cc similarity index 94% rename from cybertron/time/duration_test.cc rename to cyber/time/duration_test.cc index 271510bec8d..709088b561a 100644 --- a/cybertron/time/duration_test.cc +++ b/cyber/time/duration_test.cc @@ -14,13 +14,13 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/time/duration.h" +#include "cyber/time/duration.h" #include -#include "cybertron/time/time.h" +#include "cyber/time/time.h" #include "gtest/gtest.h" namespace apollo { -namespace cybertron { +namespace cyber { TEST(DurationTest, constructor) { Duration duration(100); @@ -64,5 +64,5 @@ TEST(DurationTest, is_zero) { EXPECT_TRUE(duration.IsZero()); } -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/time/rate.cc b/cyber/time/rate.cc similarity index 97% rename from cybertron/time/rate.cc rename to cyber/time/rate.cc index a065d7761da..aecd4c7cad4 100644 --- a/cybertron/time/rate.cc +++ b/cyber/time/rate.cc @@ -51,11 +51,11 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/time/rate.h" -#include "cybertron/common/log.h" +#include "cyber/time/rate.h" +#include "cyber/common/log.h" namespace apollo { -namespace cybertron { +namespace cyber { Rate::Rate(double frequency) : start_(Time::Now()), @@ -110,5 +110,5 @@ void Rate::Reset() { start_ = Time::Now(); } Duration Rate::CycleTime() const { return actual_cycle_time_; } -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/time/rate.h b/cyber/time/rate.h similarity index 84% rename from cybertron/time/rate.h rename to cyber/time/rate.h index 5c3374cb8e7..3003fea6fd6 100644 --- a/cybertron/time/rate.h +++ b/cyber/time/rate.h @@ -14,14 +14,14 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TIME_RATE_H_ -#define CYBERTRON_TIME_RATE_H_ +#ifndef CYBER_TIME_RATE_H_ +#define CYBER_TIME_RATE_H_ -#include "cybertron/time/duration.h" -#include "cybertron/time/time.h" +#include "cyber/time/duration.h" +#include "cyber/time/time.h" namespace apollo { -namespace cybertron { +namespace cyber { class Rate { public: @@ -39,7 +39,7 @@ class Rate { Duration actual_cycle_time_; }; -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TIME_RATE_H_ +#endif // CYBER_TIME_RATE_H_ diff --git a/cybertron/time/time.cc b/cyber/time/time.cc similarity index 98% rename from cybertron/time/time.cc rename to cyber/time/time.cc index cf1b6562cb1..8991b09246c 100644 --- a/cybertron/time/time.cc +++ b/cyber/time/time.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/time/time.h" +#include "cyber/time/time.h" #include #include @@ -23,7 +23,7 @@ #include namespace apollo { -namespace cybertron { +namespace cyber { using std::chrono::system_clock; using std::chrono::steady_clock; @@ -154,5 +154,5 @@ std::ostream& operator<<(std::ostream& os, const Time& rhs) { return os; } -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/time/time.h b/cyber/time/time.h similarity index 91% rename from cybertron/time/time.h rename to cyber/time/time.h index 1922616a5e5..354b87513f7 100644 --- a/cybertron/time/time.h +++ b/cyber/time/time.h @@ -14,15 +14,15 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TIME_TIME_H_ -#define CYBERTRON_TIME_TIME_H_ +#ifndef CYBER_TIME_TIME_H_ +#define CYBER_TIME_TIME_H_ #include #include -#include "cybertron/time/duration.h" +#include "cyber/time/duration.h" namespace apollo { -namespace cybertron { +namespace cyber { class Time { public: @@ -64,7 +64,7 @@ class Time { std::ostream& operator<<(std::ostream& os, const Time& rhs); -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TIME_TIME_H_ +#endif // CYBER_TIME_TIME_H_ diff --git a/cybertron/time/time_test.cc b/cyber/time/time_test.cc similarity index 94% rename from cybertron/time/time_test.cc rename to cyber/time/time_test.cc index a2d35107a19..618ed26292b 100644 --- a/cybertron/time/time_test.cc +++ b/cyber/time/time_test.cc @@ -14,13 +14,13 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/time/time.h" +#include "cyber/time/time.h" #include -#include "cybertron/time/duration.h" +#include "cyber/time/duration.h" #include "gtest/gtest.h" namespace apollo { -namespace cybertron { +namespace cyber { TEST(TimeTest, constructor) { Time time(100UL); @@ -69,5 +69,5 @@ TEST(TimeTest, is_zero) { EXPECT_FALSE(Time::MIN.IsZero()); } -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/timer/BUILD b/cyber/timer/BUILD similarity index 68% rename from cybertron/timer/BUILD rename to cyber/timer/BUILD index 4e27d0eef20..4bac462a3f0 100644 --- a/cybertron/timer/BUILD +++ b/cyber/timer/BUILD @@ -8,7 +8,7 @@ cc_library( hdrs = [ "timer.h", ], deps = [ "timer_manager", - "//cybertron/common:global_data", + "//cyber/common:global_data", ], ) @@ -18,10 +18,10 @@ cc_library( hdrs = [ "timer_manager.h", ], deps = [ "timing_wheel", - "//cybertron/common:macros", - "//cybertron/task:task", - "//cybertron/time:rate", - "//cybertron/time:time", + "//cyber/common:macros", + "//cyber/task:task", + "//cyber/time:rate", + "//cyber/time:time", ], ) @@ -30,7 +30,7 @@ cc_test( size = "small", srcs = [ "timer_manager_test.cc", ], deps = [ - "//cybertron:cybertron_core", + "//cyber:cyber_core", "@gtest//:main", ], ) @@ -40,8 +40,8 @@ cc_library( srcs = [ "timer_task.cc", ], hdrs = [ "timer_task.h", ], deps = [ - "//cybertron/base:bounded_queue", - "//cybertron/task:task", + "//cyber/base:bounded_queue", + "//cyber/task:task", ], ) @@ -51,7 +51,7 @@ cc_library( hdrs = [ "timing_slot.h", ], deps = [ "timer_task", - "//cybertron/base:bounded_queue", + "//cyber/base:bounded_queue", ], ) @@ -62,10 +62,10 @@ cc_library( deps = [ "timer_task", "timing_slot", - "//cybertron/base:bounded_queue", - "//cybertron/time:duration", - "//cybertron/time:time", - "//cybertron/task:task", + "//cyber/base:bounded_queue", + "//cyber/time:duration", + "//cyber/time:time", + "//cyber/task:task", ], ) @@ -74,7 +74,7 @@ cc_test( size = "small", srcs = [ "timing_wheel_test.cc", ], deps = [ - "//cybertron:cybertron_core", + "//cyber:cyber_core", "@gtest//:main", ], ) diff --git a/cybertron/timer/timer.cc b/cyber/timer/timer.cc similarity index 93% rename from cybertron/timer/timer.cc rename to cyber/timer/timer.cc index 001294a8b77..18f9cd06dfb 100644 --- a/cybertron/timer/timer.cc +++ b/cyber/timer/timer.cc @@ -14,12 +14,12 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/timer/timer.h" +#include "cyber/timer/timer.h" -#include "cybertron/common/global_data.h" +#include "cyber/common/global_data.h" namespace apollo { -namespace cybertron { +namespace cyber { Timer::Timer() { tm_ = TimerManager::Instance(); } @@ -61,5 +61,5 @@ Timer::~Timer() { } } -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/timer/timer.h b/cyber/timer/timer.h similarity index 91% rename from cybertron/timer/timer.h rename to cyber/timer/timer.h index ea13da727fe..950d3f63a97 100644 --- a/cybertron/timer/timer.h +++ b/cyber/timer/timer.h @@ -14,15 +14,15 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TIMER_TIMER_H_ -#define CYBERTRON_TIMER_TIMER_H_ +#ifndef CYBER_TIMER_TIMER_H_ +#define CYBER_TIMER_TIMER_H_ #include -#include "cybertron/timer/timer_manager.h" +#include "cyber/timer/timer_manager.h" namespace apollo { -namespace cybertron { +namespace cyber { struct TimerOption { uint32_t period; // The period of the timer, unit is ms @@ -78,7 +78,7 @@ class Timer { uint64_t timer_id_ = 0; }; -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TIMER_TIMER_H_ +#endif // CYBER_TIMER_TIMER_H_ diff --git a/cybertron/timer/timer_manager.cc b/cyber/timer/timer_manager.cc similarity index 91% rename from cybertron/timer/timer_manager.cc rename to cyber/timer/timer_manager.cc index 70bd01c0067..f929cda683f 100644 --- a/cybertron/timer/timer_manager.cc +++ b/cyber/timer/timer_manager.cc @@ -14,14 +14,14 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/timer/timer_manager.h" +#include "cyber/timer/timer_manager.h" -#include "cybertron/common/log.h" -#include "cybertron/time/duration.h" -#include "cybertron/time/rate.h" +#include "cyber/common/log.h" +#include "cyber/time/duration.h" +#include "cyber/time/rate.h" namespace apollo { -namespace cybertron { +namespace cyber { TimerManager::TimerManager() : timing_wheel_(Duration(0.01)), @@ -76,5 +76,5 @@ void TimerManager::ThreadFuncImpl() { } } -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/timer/timer_manager.h b/cyber/timer/timer_manager.h similarity index 82% rename from cybertron/timer/timer_manager.h rename to cyber/timer/timer_manager.h index e438c089485..98ceed74b15 100644 --- a/cybertron/timer/timer_manager.h +++ b/cyber/timer/timer_manager.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TIMER_TIMER_MANAGER_H_ -#define CYBERTRON_TIMER_TIMER_MANAGER_H_ +#ifndef CYBER_TIMER_TIMER_MANAGER_H_ +#define CYBER_TIMER_TIMER_MANAGER_H_ #include #include @@ -25,12 +25,12 @@ #include #include -#include "cybertron/common/macros.h" -#include "cybertron/time/duration.h" -#include "cybertron/timer/timing_wheel.h" +#include "cyber/common/macros.h" +#include "cyber/time/duration.h" +#include "cyber/timer/timing_wheel.h" namespace apollo { -namespace cybertron { +namespace cyber { class TimerManager { public: @@ -52,7 +52,7 @@ class TimerManager { DECLARE_SINGLETON(TimerManager) }; -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TIMER_TIMER_MANAGER_H_ +#endif // CYBER_TIMER_TIMER_MANAGER_H_ diff --git a/cybertron/timer/timer_manager_test.cc b/cyber/timer/timer_manager_test.cc similarity index 89% rename from cybertron/timer/timer_manager_test.cc rename to cyber/timer/timer_manager_test.cc index 5714feca38c..0c7f279f303 100644 --- a/cybertron/timer/timer_manager_test.cc +++ b/cyber/timer/timer_manager_test.cc @@ -14,15 +14,15 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/timer/timer_manager.h" +#include "cyber/timer/timer_manager.h" #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { -namespace cybertron { +namespace cyber { TEST(TimerManagerTest, Basic) { std::shared_ptr tm_ = TimerManager::Instance(); @@ -33,5 +33,5 @@ TEST(TimerManagerTest, Basic) { ASSERT_EQ(tm_->IsRunning(), false); } -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/timer/timer_task.cc b/cyber/timer/timer_task.cc similarity index 88% rename from cybertron/timer/timer_task.cc rename to cyber/timer/timer_task.cc index 66f6cf3960d..5918e5f7015 100644 --- a/cybertron/timer/timer_task.cc +++ b/cyber/timer/timer_task.cc @@ -14,12 +14,12 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/timer/timer_task.h" +#include "cyber/timer/timer_task.h" -#include "cybertron/task/task.h" +#include "cyber/task/task.h" namespace apollo { -namespace cybertron { +namespace cyber { void TimerTask::Fire(bool async) { if (status_ != INIT) { @@ -28,7 +28,7 @@ void TimerTask::Fire(bool async) { if (oneshot_) // not repeat. so always on ready status_ = EXPIRED; if (async) { - cybertron::Async(handler_); + cyber::Async(handler_); } else { handler_(); } @@ -41,5 +41,5 @@ bool TimerTask::Cancel() { status_ = CANCELED; return true; } -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/timer/timer_task.h b/cyber/timer/timer_task.h similarity index 89% rename from cybertron/timer/timer_task.h rename to cyber/timer/timer_task.h index 26bb19216eb..31e663a49cf 100644 --- a/cybertron/timer/timer_task.h +++ b/cyber/timer/timer_task.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TIMER_TIMER_TASK_H_ -#define CYBERTRON_TIMER_TIMER_TASK_H_ +#ifndef CYBER_TIMER_TIMER_TASK_H_ +#define CYBER_TIMER_TIMER_TASK_H_ #include #include @@ -28,10 +28,10 @@ #include #include -#include "cybertron/base/bounded_queue.h" +#include "cyber/base/bounded_queue.h" namespace apollo { -namespace cybertron { +namespace cyber { using CallHandler = std::function; @@ -68,7 +68,7 @@ class TimerTask { bool IsExpired() { return State() == EXPIRED; } }; -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TIMER_TIMER_TASK_H_ +#endif // CYBER_TIMER_TIMER_TASK_H_ diff --git a/cybertron/timer/timing_slot.cc b/cyber/timer/timing_slot.cc similarity index 92% rename from cybertron/timer/timing_slot.cc rename to cyber/timer/timing_slot.cc index 25d1fa17a50..c11509595ac 100644 --- a/cybertron/timer/timing_slot.cc +++ b/cyber/timer/timing_slot.cc @@ -14,13 +14,13 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/timer/timing_slot.h" +#include "cyber/timer/timing_slot.h" -#include "cybertron/common/log.h" -#include "cybertron/timer/timer_task.h" +#include "cyber/common/log.h" +#include "cyber/timer/timer_task.h" namespace apollo { -namespace cybertron { +namespace cyber { void TimingSlot::AddTask(const std::shared_ptr& task) { tasks_.emplace(task->Id(), task); @@ -61,5 +61,5 @@ void TimingSlot::EnumTaskList( } } } -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/timer/timing_slot.h b/cyber/timer/timing_slot.h similarity index 86% rename from cybertron/timer/timing_slot.h rename to cyber/timer/timing_slot.h index 8ef5337355a..d3c99fdc5ba 100644 --- a/cybertron/timer/timing_slot.h +++ b/cyber/timer/timing_slot.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TIMER_TIMING_SLOT_H_ -#define CYBERTRON_TIMER_TIMING_SLOT_H_ +#ifndef CYBER_TIMER_TIMING_SLOT_H_ +#define CYBER_TIMER_TIMING_SLOT_H_ #include #include @@ -28,12 +28,12 @@ #include #include -#include "cybertron/base/bounded_queue.h" +#include "cyber/base/bounded_queue.h" namespace apollo { -namespace cybertron { +namespace cyber { -using apollo::cybertron::base::BoundedQueue; +using apollo::cyber::base::BoundedQueue; using CallHandler = std::function; class TimerTask; @@ -58,7 +58,7 @@ class TimingSlot { BoundedQueue>* rep_list); }; // TimeSlot end -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TIMER_TIMING_SLOT_H_ +#endif // CYBER_TIMER_TIMING_SLOT_H_ diff --git a/cybertron/timer/timing_wheel.cc b/cyber/timer/timing_wheel.cc similarity index 94% rename from cybertron/timer/timing_wheel.cc rename to cyber/timer/timing_wheel.cc index 3b9a84ecc23..bb37eda803e 100644 --- a/cybertron/timer/timing_wheel.cc +++ b/cyber/timer/timing_wheel.cc @@ -14,16 +14,16 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/timer/timing_wheel.h" +#include "cyber/timer/timing_wheel.h" #include -#include "cybertron/common/log.h" -#include "cybertron/task/task.h" -#include "cybertron/time/time.h" -#include "cybertron/timer/timer_task.h" +#include "cyber/common/log.h" +#include "cyber/task/task.h" +#include "cyber/time/time.h" +#include "cyber/timer/timer_task.h" namespace apollo { -namespace cybertron { +namespace cyber { TimingWheel::TimingWheel() { if (!add_queue_.Init(BOUNDED_QUEUE_SIZE)) { @@ -105,7 +105,7 @@ void TimingWheel::Step() { while (!handler_queue_.Empty()) { HandlePackage hp; if (handler_queue_.Dequeue(&hp)) { - cybertron::Async(hp.handle); + cyber::Async(hp.handle); } } } @@ -165,5 +165,5 @@ void TimingWheel::FillSlot(const std::shared_ptr& task) { ADEBUG << "task id " << task->Id() << " insert to index " << idx; } -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/timer/timing_wheel.h b/cyber/timer/timing_wheel.h similarity index 87% rename from cybertron/timer/timing_wheel.h rename to cyber/timer/timing_wheel.h index e5f8d956dc8..9689282bccc 100644 --- a/cybertron/timer/timing_wheel.h +++ b/cyber/timer/timing_wheel.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TIMER_TIMING_WHEEL_H_ -#define CYBERTRON_TIMER_TIMING_WHEEL_H_ +#ifndef CYBER_TIMER_TIMING_WHEEL_H_ +#define CYBER_TIMER_TIMING_WHEEL_H_ #include #include @@ -28,14 +28,14 @@ #include #include -#include "cybertron/base/bounded_queue.h" -#include "cybertron/time/duration.h" -#include "cybertron/timer/timing_slot.h" +#include "cyber/base/bounded_queue.h" +#include "cyber/time/duration.h" +#include "cyber/timer/timing_slot.h" namespace apollo { -namespace cybertron { +namespace cyber { -using apollo::cybertron::base::BoundedQueue; +using apollo::cyber::base::BoundedQueue; using CallHandler = std::function; static const int TIMING_WHEEL_SIZE = 128; @@ -86,7 +86,7 @@ class TimingWheel { BoundedQueue handler_queue_; }; -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TIMER_TIMING_WHEEL_H_ +#endif // CYBER_TIMER_TIMING_WHEEL_H_ diff --git a/cybertron/timer/timing_wheel_test.cc b/cyber/timer/timing_wheel_test.cc similarity index 93% rename from cybertron/timer/timing_wheel_test.cc rename to cyber/timer/timing_wheel_test.cc index 9fc6d1d8b18..2704882baff 100644 --- a/cybertron/timer/timing_wheel_test.cc +++ b/cyber/timer/timing_wheel_test.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/timer/timing_wheel.h" +#include "cyber/timer/timing_wheel.h" #include @@ -22,10 +22,10 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { -namespace cybertron { +namespace cyber { class TestHandler { public: @@ -70,5 +70,5 @@ TEST(TimingWheelTest, Period) { } } -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/tools/BUILD b/cyber/tools/BUILD similarity index 88% rename from cybertron/tools/BUILD rename to cyber/tools/BUILD index 48b3cdfe914..7466043d437 100644 --- a/cybertron/tools/BUILD +++ b/cyber/tools/BUILD @@ -11,7 +11,7 @@ cc_binary( "cyber_recorder/**/*.h", ]), deps = [ - "//cybertron:cybertron_core", + "//cyber:cyber_core", ], linkopts = [ "-pthread", @@ -25,7 +25,7 @@ cc_binary( "cvt/monitor/*.h", ]), deps = [ - "//cybertron:cybertron_core", + "//cyber:cyber_core", ], linkopts = [ "-pthread", diff --git a/cybertron/tools/cvt/monitor/channel_msg_factory.cc b/cyber/tools/cvt/monitor/channel_msg_factory.cc similarity index 100% rename from cybertron/tools/cvt/monitor/channel_msg_factory.cc rename to cyber/tools/cvt/monitor/channel_msg_factory.cc diff --git a/cybertron/tools/cvt/monitor/channel_msg_factory.h b/cyber/tools/cvt/monitor/channel_msg_factory.h similarity index 100% rename from cybertron/tools/cvt/monitor/channel_msg_factory.h rename to cyber/tools/cvt/monitor/channel_msg_factory.h diff --git a/cybertron/tools/cvt/monitor/cybertron_channel_message.cc b/cyber/tools/cvt/monitor/cyber_channel_message.cc similarity index 95% rename from cybertron/tools/cvt/monitor/cybertron_channel_message.cc rename to cyber/tools/cvt/monitor/cyber_channel_message.cc index c032e109916..74e5a1b7e82 100644 --- a/cybertron/tools/cvt/monitor/cybertron_channel_message.cc +++ b/cyber/tools/cvt/monitor/cyber_channel_message.cc @@ -14,6 +14,6 @@ * limitations under the License. *****************************************************************************/ -#include "./cybertron_channel_message.h" +#include "./cyber_channel_message.h" double ChannelMessage::max_frmae_ratio_ = 1.0; diff --git a/cybertron/tools/cvt/monitor/cybertron_channel_message.h b/cyber/tools/cvt/monitor/cyber_channel_message.h similarity index 88% rename from cybertron/tools/cvt/monitor/cybertron_channel_message.h rename to cyber/tools/cvt/monitor/cyber_channel_message.h index 639b00d1593..e4d827d2521 100644 --- a/cybertron/tools/cvt/monitor/cybertron_channel_message.h +++ b/cyber/tools/cvt/monitor/cyber_channel_message.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef TOOLS_CVT_MONITOR_CYBERTRON_CHANNEL_MESSAGE_H_ -#define TOOLS_CVT_MONITOR_CYBERTRON_CHANNEL_MESSAGE_H_ +#ifndef TOOLS_CVT_MONITOR_CYBER_CHANNEL_MESSAGE_H_ +#define TOOLS_CVT_MONITOR_CYBER_CHANNEL_MESSAGE_H_ #include #include @@ -25,9 +25,9 @@ #include "./general_message_base.h" #include "./renderable_message.h" -#include "cybertron/cybertron.h" -#include "cybertron/time/duration.h" -#include "cybertron/time/time.h" +#include "cyber/cyber.h" +#include "cyber/time/duration.h" +#include "cyber/time/time.h" class Screen; @@ -52,11 +52,11 @@ class ChannelMessage : public GeneralMessageBase { break; case ChannelMessage::ErrorCode::CreateNodeFailed: - ret = "Cannot create Cybertron Node"; + ret = "Cannot create Cyber Node"; break; case ChannelMessage::ErrorCode::CreateReaderFailed: - ret = "Cannot create Cybertron Reader"; + ret = "Cannot create Cyber Reader"; break; case ChannelMessage::ErrorCode::MessageTypeIsEmptr: @@ -96,7 +96,7 @@ class ChannelMessage : public GeneralMessageBase { message_type_(), frame_counter_(0), frame_ratio_(0.0), - last_time_(apollo::cybertron::Time::Now()) {} + last_time_(apollo::cyber::Time::Now()) {} ~ChannelMessage() { channel_node_.reset(); } @@ -115,7 +115,7 @@ class ChannelMessage : public GeneralMessageBase { double frame_ratio(void) { if (!is_enabled_ || !has_message_come()) return 0.0; - apollo::cybertron::Time curTime = apollo::cybertron::Time::Now(); + apollo::cyber::Time curTime = apollo::cyber::Time::Now(); auto deltaTime = curTime - last_time_; if (deltaTime.ToNanosecond() > 1000000000) { @@ -169,21 +169,21 @@ class ChannelMessage : public GeneralMessageBase { std::string message_type_; int frame_counter_; double frame_ratio_; - apollo::cybertron::Time last_time_; + apollo::cyber::Time last_time_; - std::unique_ptr channel_node_; + std::unique_ptr channel_node_; std::vector readers_; std::vector writers_; }; template -class CybertronChannelMessage : public ChannelMessage { +class CyberChannelMessage : public ChannelMessage { public: - explicit CybertronChannelMessage(RenderableMessage* parent = nullptr) + explicit CyberChannelMessage(RenderableMessage* parent = nullptr) : ChannelMessage(parent) {} - ~CybertronChannelMessage() { + ~CyberChannelMessage() { channel_reader_.reset(); channel_message_.reset(); } @@ -214,7 +214,7 @@ class CybertronChannelMessage : public ChannelMessage { } std::shared_ptr channel_message_; - std::shared_ptr> channel_reader_; + std::shared_ptr> channel_reader_; mutable std::mutex inner_lock_; }; @@ -225,7 +225,7 @@ class CybertronChannelMessage : public ChannelMessage { ChannelMsgSubClass* subClass = new ChannelMsgSubClass(); \ if (subClass) { \ ret = subClass; \ - subClass->channel_node_ = apollo::cybertron::CreateNode(nodeName); \ + subClass->channel_node_ = apollo::cyber::CreateNode(nodeName); \ if (subClass->channel_node_ == nullptr) { \ delete subClass; \ subClass = nullptr; \ @@ -235,7 +235,7 @@ class CybertronChannelMessage : public ChannelMessage { [subClass](const std::shared_ptr& rawMsg) { \ subClass->updateRawMessage(rawMsg); \ }; \ - apollo::cybertron::ReaderConfig reader_cfg; \ + apollo::cyber::ReaderConfig reader_cfg; \ reader_cfg.channel_name = channelName; \ reader_cfg.pending_queue_size = 20; \ subClass->channel_reader_ = \ @@ -252,4 +252,4 @@ class CybertronChannelMessage : public ChannelMessage { return ret; \ } -#endif // TOOLS_CVT_MONITOR_CYBERTRON_CHANNEL_MESSAGE_H_ +#endif // TOOLS_CVT_MONITOR_CYBER_CHANNEL_MESSAGE_H_ diff --git a/cybertron/tools/cvt/monitor/cybertron_topology_message.cc b/cyber/tools/cvt/monitor/cyber_topology_message.cc similarity index 84% rename from cybertron/tools/cvt/monitor/cybertron_topology_message.cc rename to cyber/tools/cvt/monitor/cyber_topology_message.cc index 7bd791f0dc0..258143a881e 100644 --- a/cybertron/tools/cvt/monitor/cybertron_topology_message.cc +++ b/cyber/tools/cvt/monitor/cyber_topology_message.cc @@ -14,13 +14,14 @@ * limitations under the License. *****************************************************************************/ -#include "./cybertron_topology_message.h" +#include "./cyber_topology_message.h" #include "./channel_msg_factory.h" #include "./general_channel_message.h" #include "./screen.h" -#include "cybertron/message/message_traits.h" -#include "cybertron/proto/topology_change.pb.h" -#include "cybertron/proto/role_attributes.pb.h" + +#include "cyber/message/message_traits.h" +#include "cyber/proto/topology_change.pb.h" +#include "cyber/proto/role_attributes.pb.h" #include #include @@ -28,15 +29,15 @@ constexpr int SecondColumnOffset = 4; -CybertronTopologyMessage::CybertronTopologyMessage(const std::string& channel) +CyberTopologyMessage::CyberTopologyMessage(const std::string& channel) : RenderableMessage(nullptr, 1), second_column_(SecondColumnType::MessageFrameRatio), col1_width_(8), specified_channel_(channel), all_channels_map_() {} -CybertronTopologyMessage::~CybertronTopologyMessage(void) { - apollo::cybertron::Shutdown(); +CyberTopologyMessage::~CyberTopologyMessage(void) { + apollo::cyber::Shutdown(); for (auto item : all_channels_map_) { if (!ChannelMessage::isErrorCode(item.second)) { delete item.second; @@ -44,7 +45,7 @@ CybertronTopologyMessage::~CybertronTopologyMessage(void) { } } -RenderableMessage* CybertronTopologyMessage::Child(int lineNo) const { +RenderableMessage* CyberTopologyMessage::Child(int lineNo) const { RenderableMessage* ret = nullptr; --lineNo; @@ -70,12 +71,12 @@ RenderableMessage* CybertronTopologyMessage::Child(int lineNo) const { return ret; } -void CybertronTopologyMessage::TopologyChanged( - const apollo::cybertron::proto::ChangeMsg& changeMsg) { - if (::apollo::cybertron::proto::OperateType::OPT_JOIN == +void CyberTopologyMessage::TopologyChanged( + const apollo::cyber::proto::ChangeMsg& changeMsg) { + if (::apollo::cyber::proto::OperateType::OPT_JOIN == changeMsg.operate_type()) { bool isWriter = true; - if (::apollo::cybertron::proto::RoleType::ROLE_READER == + if (::apollo::cyber::proto::RoleType::ROLE_READER == changeMsg.role_type()) isWriter = false; AddReaderWriter(changeMsg.role_attr(), isWriter); @@ -85,7 +86,7 @@ void CybertronTopologyMessage::TopologyChanged( if (iter != all_channels_map_.cend() && !ChannelMessage::isErrorCode(iter->second)) { const std::string& nodeName = changeMsg.role_attr().node_name(); - if (::apollo::cybertron::proto::RoleType::ROLE_WRITER == + if (::apollo::cyber::proto::RoleType::ROLE_WRITER == changeMsg.role_type()) { changeMsg.role_attr(); iter->second->del_writer(nodeName); @@ -96,8 +97,8 @@ void CybertronTopologyMessage::TopologyChanged( } } -void CybertronTopologyMessage::AddReaderWriter( - const apollo::cybertron::proto::RoleAttributes& role, bool isWriter) { +void CyberTopologyMessage::AddReaderWriter( + const apollo::cyber::proto::RoleAttributes& role, bool isWriter) { const std::string& channelName = role.channel_name(); if (!specified_channel_.empty() && specified_channel_ != channelName) { @@ -133,8 +134,8 @@ void CybertronTopologyMessage::AddReaderWriter( if (!ChannelMessage::isErrorCode(channelMsg)) { if (isWriter) { - if (msgTypeName != apollo::cybertron::message::MessageType< - apollo::cybertron::message::RawMessage>()) { + if (msgTypeName != apollo::cyber::message::MessageType< + apollo::cyber::message::RawMessage>()) { channelMsg->set_message_type(msgTypeName); } @@ -145,7 +146,7 @@ void CybertronTopologyMessage::AddReaderWriter( } } -void CybertronTopologyMessage::ChangeState(const Screen* s, int key) { +void CyberTopologyMessage::ChangeState(const Screen* s, int key) { switch (key) { case 'f': case 'F': @@ -168,7 +169,7 @@ void CybertronTopologyMessage::ChangeState(const Screen* s, int key) { } } -void CybertronTopologyMessage::Render(const Screen* s, int key) { +void CyberTopologyMessage::Render(const Screen* s, int key) { page_item_count_ = s->Height() - 1; pages_ = all_channels_map_.size() / page_item_count_ + 1; ChangeState(s, key); diff --git a/cybertron/tools/cvt/monitor/cybertron_topology_message.h b/cyber/tools/cvt/monitor/cyber_topology_message.h similarity index 66% rename from cybertron/tools/cvt/monitor/cybertron_topology_message.h rename to cyber/tools/cvt/monitor/cyber_topology_message.h index 161fe7c7ccc..5be5d764032 100644 --- a/cybertron/tools/cvt/monitor/cybertron_topology_message.h +++ b/cyber/tools/cvt/monitor/cyber_topology_message.h @@ -14,38 +14,39 @@ * limitations under the License. *****************************************************************************/ -#ifndef TOOLS_CVT_MONITOR_CYBERTRON_TOPOLOGY_MESSAGE_H_ -#define TOOLS_CVT_MONITOR_CYBERTRON_TOPOLOGY_MESSAGE_H_ +#ifndef TOOLS_CVT_MONITOR_CYBER_TOPOLOGY_MESSAGE_H_ +#define TOOLS_CVT_MONITOR_CYBER_TOPOLOGY_MESSAGE_H_ #include #include #include "./renderable_message.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace proto { class ChangeMsg; class RoleAttributes; } // proto -} // cybertron +} // cyber } // apollo class ChannelMessage; // class GeneralMessage; -class CybertronTopologyMessage : public RenderableMessage { +class CyberTopologyMessage : public RenderableMessage { public: - explicit CybertronTopologyMessage(const std::string& channel); - ~CybertronTopologyMessage(); + explicit CyberTopologyMessage(const std::string& channel); + ~CyberTopologyMessage(); void Render(const Screen* s, int key) override; RenderableMessage* Child(int index) const override; - void TopologyChanged(const apollo::cybertron::proto::ChangeMsg& change_msg); - void AddReaderWriter(const apollo::cybertron::proto::RoleAttributes& role, bool isWriter); + void TopologyChanged(const apollo::cyber::proto::ChangeMsg& change_msg); + void AddReaderWriter(const apollo::cyber::proto::RoleAttributes& role, bool isWriter); + private: - CybertronTopologyMessage(const CybertronTopologyMessage&) = delete; - CybertronTopologyMessage& operator=(const CybertronTopologyMessage&) = delete; + CyberTopologyMessage(const CyberTopologyMessage&) = delete; + CyberTopologyMessage& operator=(const CyberTopologyMessage&) = delete; void ChangeState(const Screen* s, int key); @@ -57,4 +58,4 @@ class CybertronTopologyMessage : public RenderableMessage { std::map all_channels_map_; }; -#endif // TOOLS_CVT_MONITOR_CYBERTRON_TOPOLOGY_MESSAGE_H_ +#endif // TOOLS_CVT_MONITOR_CYBER_TOPOLOGY_MESSAGE_H_ diff --git a/cybertron/tools/cvt/monitor/general_channel_message.cc b/cyber/tools/cvt/monitor/general_channel_message.cc similarity index 98% rename from cybertron/tools/cvt/monitor/general_channel_message.cc rename to cyber/tools/cvt/monitor/general_channel_message.cc index f942c566382..6de8a7fd6c3 100644 --- a/cybertron/tools/cvt/monitor/general_channel_message.cc +++ b/cyber/tools/cvt/monitor/general_channel_message.cc @@ -120,7 +120,7 @@ void GeneralChannelMessage::RenderDebugString(const Screen* s, int key, unsigned lineNo) { if (has_message_come()) { if (raw_msg_class_ == nullptr) { - auto rawFactory = apollo::cybertron::message::ProtobufFactory::Instance(); + auto rawFactory = apollo::cyber::message::ProtobufFactory::Instance(); raw_msg_class_ = rawFactory->GenerateMessageByType(message_type()); } diff --git a/cybertron/tools/cvt/monitor/general_channel_message.h b/cyber/tools/cvt/monitor/general_channel_message.h similarity index 86% rename from cybertron/tools/cvt/monitor/general_channel_message.h rename to cyber/tools/cvt/monitor/general_channel_message.h index b0d26f6e0cb..60de8845191 100644 --- a/cybertron/tools/cvt/monitor/general_channel_message.h +++ b/cyber/tools/cvt/monitor/general_channel_message.h @@ -17,17 +17,17 @@ #ifndef TOOLS_CVT_MONITOR_GENERAL_CHANNEL_MESSAGE_H_ #define TOOLS_CVT_MONITOR_GENERAL_CHANNEL_MESSAGE_H_ -#include "cybertron/message/raw_message.h" -#include "cybertron_channel_message.h" +#include "cyber/message/raw_message.h" +#include "cyber_channel_message.h" #include "general_message_base.h" class RepeatedItemsMessage; class GeneralChannelMessage - : public CybertronChannelMessage { + : public CyberChannelMessage { public: ChannelMsgSubFactory(GeneralChannelMessage, - apollo::cybertron::message::RawMessage); + apollo::cyber::message::RawMessage); void Render(const Screen* s, int key) override; ~GeneralChannelMessage() { if (raw_msg_class_) { @@ -40,7 +40,7 @@ class GeneralChannelMessage private: explicit GeneralChannelMessage(RenderableMessage* parent = nullptr) - : CybertronChannelMessage(parent), + : CyberChannelMessage(parent), current_state_(State::ShowDebugString), raw_msg_class_(nullptr) {} GeneralChannelMessage(const GeneralChannelMessage&) = delete; diff --git a/cybertron/tools/cvt/monitor/general_message.cc b/cyber/tools/cvt/monitor/general_message.cc similarity index 100% rename from cybertron/tools/cvt/monitor/general_message.cc rename to cyber/tools/cvt/monitor/general_message.cc diff --git a/cybertron/tools/cvt/monitor/general_message.h b/cyber/tools/cvt/monitor/general_message.h similarity index 96% rename from cybertron/tools/cvt/monitor/general_message.h rename to cyber/tools/cvt/monitor/general_message.h index ff7b15460b8..c6f719ae8e8 100644 --- a/cybertron/tools/cvt/monitor/general_message.h +++ b/cyber/tools/cvt/monitor/general_message.h @@ -17,8 +17,8 @@ #ifndef TOOLS_CVT_MONITOR_GENERAL_MESSAGE_H_ #define TOOLS_CVT_MONITOR_GENERAL_MESSAGE_H_ -#include "cybertron/cybertron.h" -#include "cybertron/message/raw_message.h" +#include "cyber/cyber.h" +#include "cyber/message/raw_message.h" #include "general_message_base.h" class Screen; diff --git a/cybertron/tools/cvt/monitor/general_message_base.cc b/cyber/tools/cvt/monitor/general_message_base.cc similarity index 100% rename from cybertron/tools/cvt/monitor/general_message_base.cc rename to cyber/tools/cvt/monitor/general_message_base.cc diff --git a/cybertron/tools/cvt/monitor/general_message_base.h b/cyber/tools/cvt/monitor/general_message_base.h similarity index 98% rename from cybertron/tools/cvt/monitor/general_message_base.h rename to cyber/tools/cvt/monitor/general_message_base.h index e61fd2efd6f..1cf8c654586 100644 --- a/cybertron/tools/cvt/monitor/general_message_base.h +++ b/cyber/tools/cvt/monitor/general_message_base.h @@ -21,7 +21,7 @@ #include #include "./renderable_message.h" -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" class Screen; diff --git a/cybertron/tools/cvt/monitor/main.cc b/cyber/tools/cvt/monitor/main.cc similarity index 84% rename from cybertron/tools/cvt/monitor/main.cc rename to cyber/tools/cvt/monitor/main.cc index f5300828fe7..82cbd56ea12 100644 --- a/cybertron/tools/cvt/monitor/main.cc +++ b/cyber/tools/cvt/monitor/main.cc @@ -14,14 +14,14 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron_topology_message.h" +#include "cyber_topology_message.h" #include "general_channel_message.h" #include "channel_msg_factory.h" #include "screen.h" -#include "cybertron/init.h" -#include "cybertron/service_discovery/topology_manager.h" +#include "cyber/init.h" +#include "cyber/service_discovery/topology_manager.h" #include #include @@ -82,29 +82,29 @@ int main(int argc, char *argv[]) { default:; } - apollo::cybertron::Init(argv[0]); + apollo::cyber::Init(argv[0]); FLAGS_minloglevel = 3; FLAGS_alsologtostderr = 0; FLAGS_colorlogtostderr = 0; ChannelMsgFactory *f = ChannelMsgFactory::Instance(); - f->RegisterChildFactory("apollo::cybertron::message::RawMessage", + f->RegisterChildFactory("apollo::cyber::message::RawMessage", GeneralChannelMessage::Instance); - f->SetDefaultChildFactory("apollo::cybertron::message::RawMessage"); + f->SetDefaultChildFactory("apollo::cyber::message::RawMessage"); - CybertronTopologyMessage topologyMsg(val); + CyberTopologyMessage topologyMsg(val); auto topologyCallback = - [&topologyMsg](const apollo::cybertron::proto::ChangeMsg &change_msg) { + [&topologyMsg](const apollo::cyber::proto::ChangeMsg &change_msg) { topologyMsg.TopologyChanged(change_msg); }; auto channelManager = - apollo::cybertron::service_discovery::TopologyManager::Instance() + apollo::cyber::service_discovery::TopologyManager::Instance() ->channel_manager(); channelManager->AddChangeListener(topologyCallback); - std::vector roleVec; + std::vector roleVec; channelManager->GetWriters(&roleVec); for (auto &role : roleVec) { topologyMsg.AddReaderWriter(role, true); diff --git a/cybertron/tools/cvt/monitor/renderable_message.cc b/cyber/tools/cvt/monitor/renderable_message.cc similarity index 100% rename from cybertron/tools/cvt/monitor/renderable_message.cc rename to cyber/tools/cvt/monitor/renderable_message.cc diff --git a/cybertron/tools/cvt/monitor/renderable_message.h b/cyber/tools/cvt/monitor/renderable_message.h similarity index 100% rename from cybertron/tools/cvt/monitor/renderable_message.h rename to cyber/tools/cvt/monitor/renderable_message.h diff --git a/cybertron/tools/cvt/monitor/screen.cc b/cyber/tools/cvt/monitor/screen.cc similarity index 98% rename from cybertron/tools/cvt/monitor/screen.cc rename to cyber/tools/cvt/monitor/screen.cc index 4e446489bbd..80a2e9ea028 100644 --- a/cybertron/tools/cvt/monitor/screen.cc +++ b/cyber/tools/cvt/monitor/screen.cc @@ -15,8 +15,8 @@ *****************************************************************************/ #include "screen.h" -#include "cybertron_channel_message.h" -#include "cybertron_topology_message.h" +#include "cyber_channel_message.h" +#include "cyber_topology_message.h" #include "renderable_message.h" #include diff --git a/cybertron/tools/cvt/monitor/screen.h b/cyber/tools/cvt/monitor/screen.h similarity index 100% rename from cybertron/tools/cvt/monitor/screen.h rename to cyber/tools/cvt/monitor/screen.h diff --git a/cybertron/tools/cvt/vtopology/about_dialog.cc b/cyber/tools/cvt/vtopology/about_dialog.cc similarity index 100% rename from cybertron/tools/cvt/vtopology/about_dialog.cc rename to cyber/tools/cvt/vtopology/about_dialog.cc diff --git a/cybertron/tools/cvt/vtopology/about_dialog.h b/cyber/tools/cvt/vtopology/about_dialog.h similarity index 100% rename from cybertron/tools/cvt/vtopology/about_dialog.h rename to cyber/tools/cvt/vtopology/about_dialog.h diff --git a/cybertron/tools/cvt/vtopology/about_dialog.ui b/cyber/tools/cvt/vtopology/about_dialog.ui similarity index 96% rename from cybertron/tools/cvt/vtopology/about_dialog.ui rename to cyber/tools/cvt/vtopology/about_dialog.ui index dff6e6e2499..77dd12f329f 100644 --- a/cybertron/tools/cvt/vtopology/about_dialog.ui +++ b/cyber/tools/cvt/vtopology/about_dialog.ui @@ -22,7 +22,7 @@ VTopology -One Visualization Tool for Presenting Cybertron Topology +One Visualization Tool for Presenting Cyber Topology diff --git a/cybertron/tools/cvt/vtopology/arrow.cc b/cyber/tools/cvt/vtopology/arrow.cc similarity index 100% rename from cybertron/tools/cvt/vtopology/arrow.cc rename to cyber/tools/cvt/vtopology/arrow.cc diff --git a/cybertron/tools/cvt/vtopology/arrow.h b/cyber/tools/cvt/vtopology/arrow.h similarity index 100% rename from cybertron/tools/cvt/vtopology/arrow.h rename to cyber/tools/cvt/vtopology/arrow.h diff --git a/cybertron/tools/cvt/vtopology/composite_item.cc b/cyber/tools/cvt/vtopology/composite_item.cc similarity index 100% rename from cybertron/tools/cvt/vtopology/composite_item.cc rename to cyber/tools/cvt/vtopology/composite_item.cc diff --git a/cybertron/tools/cvt/vtopology/composite_item.h b/cyber/tools/cvt/vtopology/composite_item.h similarity index 100% rename from cybertron/tools/cvt/vtopology/composite_item.h rename to cyber/tools/cvt/vtopology/composite_item.h diff --git a/cybertron/tools/cvt/vtopology/interactive_graphicsview.cc b/cyber/tools/cvt/vtopology/interactive_graphicsview.cc similarity index 100% rename from cybertron/tools/cvt/vtopology/interactive_graphicsview.cc rename to cyber/tools/cvt/vtopology/interactive_graphicsview.cc diff --git a/cybertron/tools/cvt/vtopology/interactive_graphicsview.h b/cyber/tools/cvt/vtopology/interactive_graphicsview.h similarity index 100% rename from cybertron/tools/cvt/vtopology/interactive_graphicsview.h rename to cyber/tools/cvt/vtopology/interactive_graphicsview.h diff --git a/cybertron/tools/cvt/vtopology/main.cc b/cyber/tools/cvt/vtopology/main.cc similarity index 81% rename from cybertron/tools/cvt/vtopology/main.cc rename to cyber/tools/cvt/vtopology/main.cc index e60d25a8f89..56a2c149cdf 100644 --- a/cybertron/tools/cvt/vtopology/main.cc +++ b/cyber/tools/cvt/vtopology/main.cc @@ -17,22 +17,22 @@ #include #include #include "./main_window.h" -#include "cybertron/init.h" -#include "cybertron/service_discovery/topology_manager.h" +#include "cyber/init.h" +#include "cyber/service_discovery/topology_manager.h" int main(int argc, char* argv[]) { QApplication a(argc, argv); MainWindow w; - apollo::cybertron::Init(argv[0]); + apollo::cyber::Init(argv[0]); auto topologyCallback = - [&w](const apollo::cybertron::proto::ChangeMsg& change_msg) { + [&w](const apollo::cyber::proto::ChangeMsg& change_msg) { w.TopologyChanged(change_msg); }; auto channelManager = - apollo::cybertron::service_discovery::TopologyManager::Instance() + apollo::cyber::service_discovery::TopologyManager::Instance() ->channel_manager(); channelManager->AddChangeListener(topologyCallback); diff --git a/cybertron/tools/cvt/vtopology/main_window.cc b/cyber/tools/cvt/vtopology/main_window.cc similarity index 96% rename from cybertron/tools/cvt/vtopology/main_window.cc rename to cyber/tools/cvt/vtopology/main_window.cc index 19450b2629e..de0cca19bb8 100644 --- a/cybertron/tools/cvt/vtopology/main_window.cc +++ b/cyber/tools/cvt/vtopology/main_window.cc @@ -16,8 +16,8 @@ #include "./main_window.h" #include "./arrow.h" -#include "cybertron/init.h" -#include "cybertron/proto/topology_change.pb.h" +#include "cyber/init.h" +#include "cyber/proto/topology_change.pb.h" #include "ui_main_window.h" #include @@ -114,7 +114,7 @@ MainWindow::MainWindow(QWidget* parent) } MainWindow::~MainWindow() { - apollo::cybertron::Shutdown(); + apollo::cyber::Shutdown(); all_channel_root_->takeChildren(); all_reader_root_->takeChildren(); @@ -132,26 +132,26 @@ MainWindow::~MainWindow() { } void MainWindow::TopologyChanged( - const apollo::cybertron::proto::ChangeMsg& change_msg) { + const apollo::cyber::proto::ChangeMsg& change_msg) { const std::string& channelName = change_msg.role_attr().channel_name(); const std::string& nodeName = change_msg.role_attr().node_name(); ChangeSceneItemFunc changeSceneFunc = &MainWindow::AddSceneItem; if (change_msg.operate_type() == - apollo::cybertron::proto::OperateType::OPT_LEAVE) { + apollo::cyber::proto::OperateType::OPT_LEAVE) { changeSceneFunc = &MainWindow::RemoveSceneItem; } if (change_msg.change_type() == - apollo::cybertron::proto::ChangeType::CHANGE_CHANNEL) { + apollo::cyber::proto::ChangeType::CHANGE_CHANNEL) { if (change_msg.role_type() == - apollo::cybertron::proto::RoleType::ROLE_WRITER) { + apollo::cyber::proto::RoleType::ROLE_WRITER) { (this->*changeSceneFunc)(channelName, nodeName, false); } if (change_msg.role_type() == - apollo::cybertron::proto::RoleType::ROLE_READER) { + apollo::cyber::proto::RoleType::ROLE_READER) { (this->*changeSceneFunc)(channelName, nodeName, true); } } diff --git a/cybertron/tools/cvt/vtopology/main_window.h b/cyber/tools/cvt/vtopology/main_window.h similarity index 95% rename from cybertron/tools/cvt/vtopology/main_window.h rename to cyber/tools/cvt/vtopology/main_window.h index 34d4fea9f3e..58f6036c9c0 100644 --- a/cybertron/tools/cvt/vtopology/main_window.h +++ b/cyber/tools/cvt/vtopology/main_window.h @@ -42,11 +42,11 @@ class MainWindow; } namespace apollo { -namespace cybertron { +namespace cyber { namespace proto { class ChangeMsg; } -} // namespace cybertron +} // namespace cyber } // namespace apollo class MainWindow : public QMainWindow { @@ -56,7 +56,7 @@ class MainWindow : public QMainWindow { explicit MainWindow(QWidget* parent = nullptr); ~MainWindow(); - void TopologyChanged(const apollo::cybertron::proto::ChangeMsg& change_msg); + void TopologyChanged(const apollo::cyber::proto::ChangeMsg& change_msg); private slots: void UpdateSceneItem(void); diff --git a/cybertron/tools/cvt/vtopology/main_window.ui b/cyber/tools/cvt/vtopology/main_window.ui similarity index 100% rename from cybertron/tools/cvt/vtopology/main_window.ui rename to cyber/tools/cvt/vtopology/main_window.ui diff --git a/cybertron/tools/cyber_launch/cyber_launch b/cyber/tools/cyber_launch/cyber_launch similarity index 96% rename from cybertron/tools/cyber_launch/cyber_launch rename to cyber/tools/cyber_launch/cyber_launch index 851a2519aa0..e7502320455 100755 --- a/cybertron/tools/cyber_launch/cyber_launch +++ b/cyber/tools/cyber_launch/cyber_launch @@ -35,7 +35,7 @@ g_script_name = os.path.basename(sys.argv[0]).split(".")[0] g_process_pid = os.getpid() g_process_name = g_script_name + "_" + str(g_process_pid) -cybertron_path = os.getenv('CYBERTRON_PATH') +cyber_path = os.getenv('CYBER_PATH') module_path = os.getenv('MODULE_PATH') """ @@ -75,7 +75,7 @@ console.setFormatter(color_formatter) logger = logging.Logger(__name__) logger.addHandler(console) -log_dir_path = os.path.join(cybertron_path, 'log') +log_dir_path = os.path.join(cyber_path, 'log') if not os.path.exists(log_dir_path): os.makedirs(log_dir_path) log_file_path = os.path.join(log_dir_path, 'cyber_launch.' + str(g_process_pid)) @@ -297,7 +297,7 @@ def start(launch_file = ''): if module_path != None and os.path.exists(os.path.join(module_path, 'launch', launch_file)): launch_file = os.path.join(module_path, 'launch', launch_file) else: - launch_file = os.path.join(cybertron_path, 'launch', launch_file) + launch_file = os.path.join(cyber_path, 'launch', launch_file) else: if os.path.exists(os.path.join(g_pwd, launch_file)): launch_file = os.path.join(g_pwd, launch_file) @@ -394,7 +394,7 @@ def start(launch_file = ''): try: process_name = process_name.replace('${MODULE_PATH}', os.environ['MODULE_PATH']) except KeyError: - process_name = process_name.replace('${MODULE_PATH}', os.environ['CYBERTRON_PATH']) + process_name = process_name.replace('${MODULE_PATH}', os.environ['CYBER_PATH']) pw = ProcessWrapper(process_name.split()[0], 0, [""], process_name, process_type, exception_handler) # default is library else: @@ -416,7 +416,7 @@ def start(launch_file = ''): if not all_died: logger.info("Stop all processes...") stop() - logger.info("Cybertron exit.") + logger.info("Cyber exit.") def stop(sig = signal.SIGINT): """ @@ -459,22 +459,22 @@ def signal_handler(sig, frame): def main(): """ main function """ - cybertron_path = os.getenv('CYBERTRON_PATH') - if cybertron_path == None: - logger.error('Error: environment variable CYBERTRON_PATH not found, set environment first.') + cyber_path = os.getenv('CYBER_PATH') + if cyber_path == None: + logger.error('Error: environment variable CYBER_PATH not found, set environment first.') sys.exit(1) - os.chdir(cybertron_path) - parser = argparse.ArgumentParser(description='cybertron launcher') + os.chdir(cyber_path) + parser = argparse.ArgumentParser(description='cyber launcher') subparsers = parser.add_subparsers(help='sub-command help') start_parser = subparsers.add_parser('start', help='launch/benchmark.launch') - start_parser.add_argument('file', nargs='?', action='store', help='launch file, default is cybertron.launch') + start_parser.add_argument('file', nargs='?', action='store', help='launch file, default is cyber.launch') stop_parser = subparsers.add_parser('stop', help='stop all the module in launch file') stop_parser.add_argument('file', nargs='?', action='store', help='launch file, default stop all the launcher') #restart_parser = subparsers.add_parser('restart', help='restart the module') - #restart_parser.add_argument('file', nargs='?', action='store', help='launch file, default is cybertron.launch') + #restart_parser.add_argument('file', nargs='?', action='store', help='launch file, default is cyber.launch') params = parser.parse_args(sys.argv[1:]) diff --git a/cybertron/tools/cyber_recorder/info.cc b/cyber/tools/cyber_recorder/info.cc similarity index 97% rename from cybertron/tools/cyber_recorder/info.cc rename to cyber/tools/cyber_recorder/info.cc index eb14d5f1b34..9c8e4cb7463 100644 --- a/cybertron/tools/cyber_recorder/info.cc +++ b/cyber/tools/cyber_recorder/info.cc @@ -14,10 +14,10 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/tools/cyber_recorder/info.h" +#include "cyber/tools/cyber_recorder/info.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace record { Info::Info() {} @@ -116,5 +116,5 @@ bool Info::Display(const std::string& file) { } } // namespace record -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/tools/cyber_recorder/info.h b/cyber/tools/cyber_recorder/info.h similarity index 72% rename from cybertron/tools/cyber_recorder/info.h rename to cyber/tools/cyber_recorder/info.h index 12c4a21a51a..d5aefc380f8 100644 --- a/cybertron/tools/cyber_recorder/info.h +++ b/cyber/tools/cyber_recorder/info.h @@ -14,20 +14,20 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TOOLS_CYBER_RECORDER_INFO_H_ -#define CYBERTRON_TOOLS_CYBER_RECORDER_INFO_H_ +#ifndef CYBER_TOOLS_CYBER_RECORDER_INFO_H_ +#define CYBER_TOOLS_CYBER_RECORDER_INFO_H_ #include #include #include -#include "cybertron/common/time_conversion.h" -#include "cybertron/proto/record.pb.h" -#include "cybertron/record/record_file.h" +#include "cyber/common/time_conversion.h" +#include "cyber/proto/record.pb.h" +#include "cyber/record/record_file.h" -using ::apollo::cybertron::common::UnixSecondsToString; +using ::apollo::cyber::common::UnixSecondsToString; namespace apollo { -namespace cybertron { +namespace cyber { namespace record { class Info { @@ -38,7 +38,7 @@ class Info { }; } // namespace record -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TOOLS_CYBER_RECORDER_INFO_H_ +#endif // CYBER_TOOLS_CYBER_RECORDER_INFO_H_ diff --git a/cybertron/tools/cyber_recorder/main.cc b/cyber/tools/cyber_recorder/main.cc similarity index 91% rename from cybertron/tools/cyber_recorder/main.cc rename to cyber/tools/cyber_recorder/main.cc index f6ab75bee79..1cdd96e1d15 100644 --- a/cybertron/tools/cyber_recorder/main.cc +++ b/cyber/tools/cyber_recorder/main.cc @@ -21,24 +21,24 @@ #include #include -#include "cybertron/common/file.h" -#include "cybertron/common/time_conversion.h" -#include "cybertron/init.h" -#include "cybertron/tools/cyber_recorder/info.h" -#include "cybertron/tools/cyber_recorder/player/player.h" -#include "cybertron/tools/cyber_recorder/recorder.h" -#include "cybertron/tools/cyber_recorder/recoverer.h" -#include "cybertron/tools/cyber_recorder/spliter.h" +#include "cyber/common/file.h" +#include "cyber/common/time_conversion.h" +#include "cyber/init.h" +#include "cyber/tools/cyber_recorder/info.h" +#include "cyber/tools/cyber_recorder/player/player.h" +#include "cyber/tools/cyber_recorder/recorder.h" +#include "cyber/tools/cyber_recorder/recoverer.h" +#include "cyber/tools/cyber_recorder/spliter.h" -using apollo::cybertron::common::GetFileName; -using apollo::cybertron::common::StringToUnixSeconds; -using apollo::cybertron::common::UnixSecondsToString; -using apollo::cybertron::record::Info; -using apollo::cybertron::record::Player; -using apollo::cybertron::record::PlayParam; -using apollo::cybertron::record::Recorder; -using apollo::cybertron::record::Recoverer; -using apollo::cybertron::record::Spliter; +using apollo::cyber::common::GetFileName; +using apollo::cyber::common::StringToUnixSeconds; +using apollo::cyber::common::UnixSecondsToString; +using apollo::cyber::record::Info; +using apollo::cyber::record::Player; +using apollo::cyber::record::PlayParam; +using apollo::cyber::record::Recorder; +using apollo::cyber::record::Recoverer; +using apollo::cyber::record::Spliter; const char INFO_OPTIONS[] = "f:h"; const char RECORD_OPTIONS[] = "o:ac:h"; @@ -285,13 +285,13 @@ int main(int argc, char** argv) { std::cout << "MUST specify file option (-f)." << std::endl; return -1; } - ::apollo::cybertron::Init(argv[0]); + ::apollo::cyber::Init(argv[0]); Info info; bool info_result = true; for (auto& opt_file : opt_file_vec) { info_result = info_result && info.Display(opt_file) ? true : false; } - ::apollo::cybertron::Shutdown(); + ::apollo::cyber::Shutdown(); return info_result ? 0 : -1; } else if (command == "recover") { if (opt_file_vec.empty()) { @@ -306,10 +306,10 @@ int main(int argc, char** argv) { std::string default_output_file = opt_file_vec[0] + ".recover"; opt_output_vec.push_back(default_output_file); } - ::apollo::cybertron::Init(argv[0]); + ::apollo::cyber::Init(argv[0]); Recoverer recoverer(opt_file_vec[0], opt_output_vec[0]); bool recover_result = recoverer.Proc(); - ::apollo::cybertron::Shutdown(); + ::apollo::cyber::Shutdown(); return recover_result ? 0 : -1; } @@ -318,7 +318,7 @@ int main(int argc, char** argv) { std::cout << "MUST specify file option (-f)." << std::endl; return -1; } - ::apollo::cybertron::Init(argv[0]); + ::apollo::cyber::Init(argv[0]); bool play_result = true; PlayParam play_param; play_param.is_play_all_channels = opt_white_channels.empty(); @@ -334,7 +334,7 @@ int main(int argc, char** argv) { Player player(play_param); play_result = play_result && player.Init() ? true : false; play_result = play_result && player.Start() ? true : false; - ::apollo::cybertron::Shutdown(); + ::apollo::cyber::Shutdown(); return play_result ? 0 : -1; } else if (command == "record") { if (opt_white_channels.empty() && !opt_all) { @@ -353,17 +353,17 @@ int main(int argc, char** argv) { opt_output_vec.push_back(default_output_file); } bool record_result = true; - ::apollo::cybertron::Init(argv[0]); + ::apollo::cyber::Init(argv[0]); auto recorder = std::make_shared(opt_output_vec[0], opt_all, opt_white_channels); record_result = record_result && recorder->Start() ? true : false; if (record_result) { - while (::apollo::cybertron::OK()) { + while (::apollo::cyber::OK()) { std::this_thread::sleep_for(std::chrono::milliseconds(100)); } record_result = record_result && recorder->Stop() ? true : false; } - ::apollo::cybertron::Shutdown(); + ::apollo::cyber::Shutdown(); return record_result ? 0 : -1; } else if (command == "split") { if (opt_file_vec.empty()) { @@ -378,11 +378,11 @@ int main(int argc, char** argv) { std::string default_output_file = opt_file_vec[0] + ".split"; opt_output_vec.push_back(default_output_file); } - ::apollo::cybertron::Init(argv[0]); + ::apollo::cyber::Init(argv[0]); Spliter spliter(opt_file_vec[0], opt_output_vec[0], opt_white_channels, opt_black_channels, opt_begin, opt_end); bool split_result = spliter.Proc(); - ::apollo::cybertron::Shutdown(); + ::apollo::cyber::Shutdown(); return split_result ? 0 : -1; } diff --git a/cybertron/tools/cyber_recorder/player/play_param.h b/cyber/tools/cyber_recorder/player/play_param.h similarity index 84% rename from cybertron/tools/cyber_recorder/player/play_param.h rename to cyber/tools/cyber_recorder/player/play_param.h index 39124dc4cf3..8f4423de597 100644 --- a/cybertron/tools/cyber_recorder/player/play_param.h +++ b/cyber/tools/cyber_recorder/player/play_param.h @@ -14,15 +14,15 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TOOLS_CYBER_RECORDER_PLAYER_PLAY_PARAM_H_ -#define CYBERTRON_TOOLS_CYBER_RECORDER_PLAYER_PLAY_PARAM_H_ +#ifndef CYBER_TOOLS_CYBER_RECORDER_PLAYER_PLAY_PARAM_H_ +#define CYBER_TOOLS_CYBER_RECORDER_PLAYER_PLAY_PARAM_H_ #include #include #include namespace apollo { -namespace cybertron { +namespace cyber { namespace record { struct PlayParam { @@ -38,7 +38,7 @@ struct PlayParam { }; } // namespace record -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TOOLS_CYBER_RECORDER_PLAYER_PLAY_PARAM_H_ +#endif // CYBER_TOOLS_CYBER_RECORDER_PLAYER_PLAY_PARAM_H_ diff --git a/cybertron/tools/cyber_recorder/player/play_task.cc b/cyber/tools/cyber_recorder/player/play_task.cc similarity index 92% rename from cybertron/tools/cyber_recorder/player/play_task.cc rename to cyber/tools/cyber_recorder/player/play_task.cc index bd2aaa72979..ab82b869dd3 100644 --- a/cybertron/tools/cyber_recorder/player/play_task.cc +++ b/cyber/tools/cyber_recorder/player/play_task.cc @@ -14,12 +14,12 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/tools/cyber_recorder/player/play_task.h" +#include "cyber/tools/cyber_recorder/player/play_task.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace record { std::atomic PlayTask::played_msg_num_ = {0}; @@ -52,5 +52,5 @@ void PlayTask::Play() { } } // namespace record -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/tools/cyber_recorder/player/play_task.h b/cyber/tools/cyber_recorder/player/play_task.h similarity index 83% rename from cybertron/tools/cyber_recorder/player/play_task.h rename to cyber/tools/cyber_recorder/player/play_task.h index 1c353e2495c..f7e945fdabb 100644 --- a/cybertron/tools/cyber_recorder/player/play_task.h +++ b/cyber/tools/cyber_recorder/player/play_task.h @@ -14,18 +14,18 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TOOLS_CYBER_RECORDER_PLAYER_PLAY_TASK_H_ -#define CYBERTRON_TOOLS_CYBER_RECORDER_PLAYER_PLAY_TASK_H_ +#ifndef CYBER_TOOLS_CYBER_RECORDER_PLAYER_PLAY_TASK_H_ +#define CYBER_TOOLS_CYBER_RECORDER_PLAYER_PLAY_TASK_H_ #include #include #include -#include "cybertron/message/raw_message.h" -#include "cybertron/node/writer.h" +#include "cyber/message/raw_message.h" +#include "cyber/node/writer.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace record { class PlayTask { @@ -53,7 +53,7 @@ class PlayTask { }; } // namespace record -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TOOLS_CYBER_RECORDER_PLAYER_PLAY_TASK_H_ +#endif // CYBER_TOOLS_CYBER_RECORDER_PLAYER_PLAY_TASK_H_ diff --git a/cybertron/tools/cyber_recorder/player/play_task_buffer.cc b/cyber/tools/cyber_recorder/player/play_task_buffer.cc similarity index 93% rename from cybertron/tools/cyber_recorder/player/play_task_buffer.cc rename to cyber/tools/cyber_recorder/player/play_task_buffer.cc index 2dd656ac9a0..ff3050bfd90 100644 --- a/cybertron/tools/cyber_recorder/player/play_task_buffer.cc +++ b/cyber/tools/cyber_recorder/player/play_task_buffer.cc @@ -14,10 +14,10 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/tools/cyber_recorder/player/play_task_buffer.h" +#include "cyber/tools/cyber_recorder/player/play_task_buffer.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace record { PlayTaskBuffer::PlayTaskBuffer() {} @@ -53,5 +53,5 @@ PlayTaskBuffer::TaskPtr PlayTaskBuffer::Pop() { } } // namespace record -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/tools/cyber_recorder/player/play_task_buffer.h b/cyber/tools/cyber_recorder/player/play_task_buffer.h similarity index 81% rename from cybertron/tools/cyber_recorder/player/play_task_buffer.h rename to cyber/tools/cyber_recorder/player/play_task_buffer.h index 9a1d3edc24c..5c3d32f3271 100644 --- a/cybertron/tools/cyber_recorder/player/play_task_buffer.h +++ b/cyber/tools/cyber_recorder/player/play_task_buffer.h @@ -14,18 +14,18 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TOOLS_CYBER_RECORDER_PLAYER_PLAY_TASK_BUFFER_H_ -#define CYBERTRON_TOOLS_CYBER_RECORDER_PLAYER_PLAY_TASK_BUFFER_H_ +#ifndef CYBER_TOOLS_CYBER_RECORDER_PLAYER_PLAY_TASK_BUFFER_H_ +#define CYBER_TOOLS_CYBER_RECORDER_PLAYER_PLAY_TASK_BUFFER_H_ #include #include #include #include -#include "cybertron/tools/cyber_recorder/player/play_task.h" +#include "cyber/tools/cyber_recorder/player/play_task.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace record { class PlayTaskBuffer { @@ -49,7 +49,7 @@ class PlayTaskBuffer { }; } // namespace record -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TOOLS_CYBER_RECORDER_PLAYER_PLAY_TASK_BUFFER_H_ +#endif // CYBER_TOOLS_CYBER_RECORDER_PLAYER_PLAY_TASK_BUFFER_H_ diff --git a/cybertron/tools/cyber_recorder/player/play_task_consumer.cc b/cyber/tools/cyber_recorder/player/play_task_consumer.cc similarity index 95% rename from cybertron/tools/cyber_recorder/player/play_task_consumer.cc rename to cyber/tools/cyber_recorder/player/play_task_consumer.cc index 39ffe131883..bd459a0c0e9 100644 --- a/cybertron/tools/cyber_recorder/player/play_task_consumer.cc +++ b/cyber/tools/cyber_recorder/player/play_task_consumer.cc @@ -14,13 +14,13 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/tools/cyber_recorder/player/play_task_consumer.h" +#include "cyber/tools/cyber_recorder/player/play_task_consumer.h" -#include "cybertron/common/log.h" -#include "cybertron/time/time.h" +#include "cyber/common/log.h" +#include "cyber/time/time.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace record { const uint64_t PlayTaskConsumer::kPauseSleepNanoSec = 100000000UL; @@ -110,5 +110,5 @@ void PlayTaskConsumer::ThreadFunc() { } } // namespace record -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/tools/cyber_recorder/player/play_task_consumer.h b/cyber/tools/cyber_recorder/player/play_task_consumer.h similarity index 86% rename from cybertron/tools/cyber_recorder/player/play_task_consumer.h rename to cyber/tools/cyber_recorder/player/play_task_consumer.h index 140e04d94ed..ac38b27e11d 100644 --- a/cybertron/tools/cyber_recorder/player/play_task_consumer.h +++ b/cyber/tools/cyber_recorder/player/play_task_consumer.h @@ -14,18 +14,18 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TOOLS_CYBER_RECORDER_PLAYER_PLAY_TASK_CONSUMER_H_ -#define CYBERTRON_TOOLS_CYBER_RECORDER_PLAYER_PLAY_TASK_CONSUMER_H_ +#ifndef CYBER_TOOLS_CYBER_RECORDER_PLAYER_PLAY_TASK_CONSUMER_H_ +#define CYBER_TOOLS_CYBER_RECORDER_PLAYER_PLAY_TASK_CONSUMER_H_ #include #include #include #include -#include "cybertron/tools/cyber_recorder/player/play_task_buffer.h" +#include "cyber/tools/cyber_recorder/player/play_task_buffer.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace record { class PlayTaskConsumer { @@ -65,7 +65,7 @@ class PlayTaskConsumer { }; } // namespace record -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TOOLS_CYBER_RECORDER_PLAYER_PLAY_TASK_CONSUMER_H_ +#endif // CYBER_TOOLS_CYBER_RECORDER_PLAYER_PLAY_TASK_CONSUMER_H_ diff --git a/cybertron/tools/cyber_recorder/player/play_task_producer.cc b/cyber/tools/cyber_recorder/player/play_task_producer.cc similarity index 96% rename from cybertron/tools/cyber_recorder/player/play_task_producer.cc rename to cyber/tools/cyber_recorder/player/play_task_producer.cc index 11dd9efa35d..9e520e48f5c 100644 --- a/cybertron/tools/cyber_recorder/player/play_task_producer.cc +++ b/cyber/tools/cyber_recorder/player/play_task_producer.cc @@ -14,17 +14,17 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/tools/cyber_recorder/player/play_task_producer.h" +#include "cyber/tools/cyber_recorder/player/play_task_producer.h" #include -#include "cybertron/common/log.h" -#include "cybertron/cybertron.h" -#include "cybertron/message/protobuf_factory.h" -#include "cybertron/record/record_viewer.h" +#include "cyber/common/log.h" +#include "cyber/cyber.h" +#include "cyber/message/protobuf_factory.h" +#include "cyber/record/record_viewer.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace record { const uint32_t PlayTaskProducer::kMinTaskBufferSize = 500; @@ -174,7 +174,7 @@ bool PlayTaskProducer::UpdatePlayParam() { bool PlayTaskProducer::CreateWriters() { std::string node_name = "cyber_recorder_play_" + std::to_string(getpid()); - node_ = apollo::cybertron::CreateNode(node_name); + node_ = apollo::cyber::CreateNode(node_name); if (node_ == nullptr) { AERROR << "create node failed."; return false; @@ -279,5 +279,5 @@ void PlayTaskProducer::CreateTask(uint64_t begin_time_ns, uint64_t end_time_ns, } } // namespace record -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/tools/cyber_recorder/player/play_task_producer.h b/cyber/tools/cyber_recorder/player/play_task_producer.h similarity index 83% rename from cybertron/tools/cyber_recorder/player/play_task_producer.h rename to cyber/tools/cyber_recorder/player/play_task_producer.h index 5f54ae2d555..7bf1b102656 100644 --- a/cybertron/tools/cyber_recorder/player/play_task_producer.h +++ b/cyber/tools/cyber_recorder/player/play_task_producer.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TOOLS_CYBER_RECORDER_PLAYER_PLAY_TASK_PRODUCER_H_ -#define CYBERTRON_TOOLS_CYBER_RECORDER_PLAYER_PLAY_TASK_PRODUCER_H_ +#ifndef CYBER_TOOLS_CYBER_RECORDER_PLAYER_PLAY_TASK_PRODUCER_H_ +#define CYBER_TOOLS_CYBER_RECORDER_PLAYER_PLAY_TASK_PRODUCER_H_ #include #include @@ -26,15 +26,15 @@ #include #include -#include "cybertron/message/raw_message.h" -#include "cybertron/node/node.h" -#include "cybertron/node/writer.h" -#include "cybertron/record/record_reader.h" -#include "cybertron/tools/cyber_recorder/player/play_param.h" -#include "cybertron/tools/cyber_recorder/player/play_task_buffer.h" +#include "cyber/message/raw_message.h" +#include "cyber/node/node.h" +#include "cyber/node/writer.h" +#include "cyber/record/record_reader.h" +#include "cyber/tools/cyber_recorder/player/play_param.h" +#include "cyber/tools/cyber_recorder/player/play_task_buffer.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace record { struct RecordInfo { @@ -95,7 +95,7 @@ class PlayTaskProducer { }; } // namespace record -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TOOLS_CYBER_RECORDER_PLAYER_PLAY_TASK_PRODUCER_H_ +#endif // CYBER_TOOLS_CYBER_RECORDER_PLAYER_PLAY_TASK_PRODUCER_H_ diff --git a/cybertron/tools/cyber_recorder/player/player.cc b/cyber/tools/cyber_recorder/player/player.cc similarity index 95% rename from cybertron/tools/cyber_recorder/player/player.cc rename to cyber/tools/cyber_recorder/player/player.cc index b9672e63596..f3783b2d2e1 100644 --- a/cybertron/tools/cyber_recorder/player/player.cc +++ b/cyber/tools/cyber_recorder/player/player.cc @@ -14,14 +14,14 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/tools/cyber_recorder/player/player.h" +#include "cyber/tools/cyber_recorder/player/player.h" #include -#include "cybertron/init.h" +#include "cyber/init.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace record { const uint64_t Player::kSleepIntervalMiliSec = 100; @@ -86,7 +86,7 @@ bool Player::Start() { (double)(play_param.end_time_ns - play_param.begin_time_ns) / 1e9 + (double)play_param.start_time_s; - while (!is_stopped_.load() && apollo::cybertron::OK()) { + while (!is_stopped_.load() && apollo::cyber::OK()) { auto character = term_ctrl_->ReadChar(); switch (character) { case ' ': @@ -148,5 +148,5 @@ bool Player::Stop() { } } // namespace record -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/tools/cyber_recorder/player/player.h b/cyber/tools/cyber_recorder/player/player.h similarity index 73% rename from cybertron/tools/cyber_recorder/player/player.h rename to cyber/tools/cyber_recorder/player/player.h index 874eaacac91..773ec796a6f 100644 --- a/cybertron/tools/cyber_recorder/player/player.h +++ b/cyber/tools/cyber_recorder/player/player.h @@ -14,21 +14,21 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TOOLS_CYBER_RECORDER_PLAYER_PLAYER_H_ -#define CYBERTRON_TOOLS_CYBER_RECORDER_PLAYER_PLAYER_H_ +#ifndef CYBER_TOOLS_CYBER_RECORDER_PLAYER_PLAYER_H_ +#define CYBER_TOOLS_CYBER_RECORDER_PLAYER_PLAYER_H_ #include #include #include -#include "cybertron/tools/cyber_recorder/player/play_param.h" -#include "cybertron/tools/cyber_recorder/player/play_task_buffer.h" -#include "cybertron/tools/cyber_recorder/player/play_task_consumer.h" -#include "cybertron/tools/cyber_recorder/player/play_task_producer.h" -#include "cybertron/tools/cyber_recorder/player/terminal_controller.h" +#include "cyber/tools/cyber_recorder/player/play_param.h" +#include "cyber/tools/cyber_recorder/player/play_task_buffer.h" +#include "cyber/tools/cyber_recorder/player/play_task_consumer.h" +#include "cyber/tools/cyber_recorder/player/play_task_producer.h" +#include "cyber/tools/cyber_recorder/player/terminal_controller.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace record { class Player { @@ -56,7 +56,7 @@ class Player { }; } // namespace record -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TOOLS_CYBER_RECORDER_PLAYER_PLAYER_H_ \ No newline at end of file +#endif // CYBER_TOOLS_CYBER_RECORDER_PLAYER_PLAYER_H_ \ No newline at end of file diff --git a/cybertron/tools/cyber_recorder/player/terminal_controller.cc b/cyber/tools/cyber_recorder/player/terminal_controller.cc similarity index 93% rename from cybertron/tools/cyber_recorder/player/terminal_controller.cc rename to cyber/tools/cyber_recorder/player/terminal_controller.cc index f807f3d79eb..99e819d2e62 100644 --- a/cybertron/tools/cyber_recorder/player/terminal_controller.cc +++ b/cyber/tools/cyber_recorder/player/terminal_controller.cc @@ -14,12 +14,12 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/tools/cyber_recorder/player/terminal_controller.h" +#include "cyber/tools/cyber_recorder/player/terminal_controller.h" #include namespace apollo { -namespace cybertron { +namespace cyber { namespace record { TerminalController::TerminalController() : max_fd_(0) {} @@ -59,5 +59,5 @@ char TerminalController::ReadChar() { } } // namespace record -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/tools/cyber_recorder/player/terminal_controller.h b/cyber/tools/cyber_recorder/player/terminal_controller.h similarity index 81% rename from cybertron/tools/cyber_recorder/player/terminal_controller.h rename to cyber/tools/cyber_recorder/player/terminal_controller.h index 1b6111d995e..2bcb297ef0e 100644 --- a/cybertron/tools/cyber_recorder/player/terminal_controller.h +++ b/cyber/tools/cyber_recorder/player/terminal_controller.h @@ -14,15 +14,15 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TOOLS_CYBER_RECORDER_PLAYER_TERMINAL_CONTROLLER_H_ -#define CYBERTRON_TOOLS_CYBER_RECORDER_PLAYER_TERMINAL_CONTROLLER_H_ +#ifndef CYBER_TOOLS_CYBER_RECORDER_PLAYER_TERMINAL_CONTROLLER_H_ +#define CYBER_TOOLS_CYBER_RECORDER_PLAYER_TERMINAL_CONTROLLER_H_ #include #include #include namespace apollo { -namespace cybertron { +namespace cyber { namespace record { class TerminalController { @@ -41,7 +41,7 @@ class TerminalController { }; } // namespace record -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TOOLS_CYBER_RECORDER_PLAYER_TERMINAL_CONTROLLER_H_ +#endif // CYBER_TOOLS_CYBER_RECORDER_PLAYER_TERMINAL_CONTROLLER_H_ diff --git a/cybertron/tools/cyber_recorder/recorder.cc b/cyber/tools/cyber_recorder/recorder.cc similarity index 96% rename from cybertron/tools/cyber_recorder/recorder.cc rename to cyber/tools/cyber_recorder/recorder.cc index 4e972c13c6e..0cd4f331f47 100644 --- a/cybertron/tools/cyber_recorder/recorder.cc +++ b/cyber/tools/cyber_recorder/recorder.cc @@ -14,10 +14,10 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/tools/cyber_recorder/recorder.h" +#include "cyber/tools/cyber_recorder/recorder.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace record { Recorder::Recorder(const std::string& output, bool all_channels, @@ -35,7 +35,7 @@ bool Recorder::Start() { return false; } std::string node_name = "cyber_recorder_record_" + std::to_string(getpid()); - node_ = ::apollo::cybertron::CreateNode(node_name); + node_ = ::apollo::cyber::CreateNode(node_name); if (node_ == nullptr) { AERROR << "create node failed, node: " << node_name; return false; @@ -65,7 +65,7 @@ bool Recorder::Stop() { void Recorder::TopologyCallback(const ChangeMsg& change_message) { ADEBUG << "ChangeMsg in Topology Callback:" << std::endl << change_message.ShortDebugString(); - if (change_message.role_type() != apollo::cybertron::proto::ROLE_WRITER) { + if (change_message.role_type() != apollo::cyber::proto::ROLE_WRITER) { ADEBUG << "Change message role type is not ROLE_WRITER."; return; } @@ -182,5 +182,5 @@ void Recorder::ReaderCallback(const std::shared_ptr& message, } } // namespace record -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/tools/cyber_recorder/recorder.h b/cyber/tools/cyber_recorder/recorder.h similarity index 68% rename from cybertron/tools/cyber_recorder/recorder.h rename to cyber/tools/cyber_recorder/recorder.h index a358f187106..30cc8340013 100644 --- a/cybertron/tools/cyber_recorder/recorder.h +++ b/cyber/tools/cyber_recorder/recorder.h @@ -14,34 +14,34 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TOOLS_CYBER_RECORDER_RECORDER_H_ -#define CYBERTRON_TOOLS_CYBER_RECORDER_RECORDER_H_ +#ifndef CYBER_TOOLS_CYBER_RECORDER_RECORDER_H_ +#define CYBER_TOOLS_CYBER_RECORDER_RECORDER_H_ #include #include #include #include #include -#include "cybertron/base/signal.h" -#include "cybertron/cybertron.h" -#include "cybertron/message/raw_message.h" -#include "cybertron/proto/record_conf.pb.h" -#include "cybertron/proto/topology_change.pb.h" -#include "cybertron/record/record_writer.h" +#include "cyber/base/signal.h" +#include "cyber/cyber.h" +#include "cyber/message/raw_message.h" +#include "cyber/proto/record_conf.pb.h" +#include "cyber/proto/topology_change.pb.h" +#include "cyber/record/record_writer.h" -using apollo::cybertron::service_discovery::TopologyManager; -using apollo::cybertron::service_discovery::ChannelManager; -using apollo::cybertron::proto::ChangeMsg; -using apollo::cybertron::proto::RecordConf; -using apollo::cybertron::proto::RoleType; -using apollo::cybertron::proto::RoleAttributes; -using apollo::cybertron::message::RawMessage; -using apollo::cybertron::base::Connection; -using apollo::cybertron::ReaderBase; -using apollo::cybertron::Node; +using apollo::cyber::service_discovery::TopologyManager; +using apollo::cyber::service_discovery::ChannelManager; +using apollo::cyber::proto::ChangeMsg; +using apollo::cyber::proto::RecordConf; +using apollo::cyber::proto::RoleType; +using apollo::cyber::proto::RoleAttributes; +using apollo::cyber::message::RawMessage; +using apollo::cyber::base::Connection; +using apollo::cyber::ReaderBase; +using apollo::cyber::Node; namespace apollo { -namespace cybertron { +namespace cyber { namespace record { class Recorder : public std::enable_shared_from_this { @@ -81,7 +81,7 @@ class Recorder : public std::enable_shared_from_this { }; } // namespace record -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TOOLS_CYBER_RECORDER_RECORDER_H_ +#endif // CYBER_TOOLS_CYBER_RECORDER_RECORDER_H_ diff --git a/cybertron/tools/cyber_recorder/recoverer.cc b/cyber/tools/cyber_recorder/recoverer.cc similarity index 96% rename from cybertron/tools/cyber_recorder/recoverer.cc rename to cyber/tools/cyber_recorder/recoverer.cc index 5ecfe2e43dd..81bbf5d4030 100644 --- a/cybertron/tools/cyber_recorder/recoverer.cc +++ b/cyber/tools/cyber_recorder/recoverer.cc @@ -14,12 +14,12 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/tools/cyber_recorder/recoverer.h" +#include "cyber/tools/cyber_recorder/recoverer.h" -#include "cybertron/record/header_builder.h" +#include "cyber/record/header_builder.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace record { Recoverer::Recoverer(const std::string& input_file, @@ -131,5 +131,5 @@ bool Recoverer::Proc() { } // end for Proc() } // namespace record -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/tools/cyber_recorder/recoverer.h b/cyber/tools/cyber_recorder/recoverer.h similarity index 69% rename from cybertron/tools/cyber_recorder/recoverer.h rename to cyber/tools/cyber_recorder/recoverer.h index c3177055afc..03e63308c23 100644 --- a/cybertron/tools/cyber_recorder/recoverer.h +++ b/cyber/tools/cyber_recorder/recoverer.h @@ -14,26 +14,26 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TOOLS_CYBER_RECORDER_RECOVERER_H_ -#define CYBERTRON_TOOLS_CYBER_RECORDER_RECOVERER_H_ +#ifndef CYBER_TOOLS_CYBER_RECORDER_RECOVERER_H_ +#define CYBER_TOOLS_CYBER_RECORDER_RECOVERER_H_ #include #include #include #include -#include "cybertron/common/log.h" -#include "cybertron/proto/record.pb.h" -#include "cybertron/record/record_file.h" -#include "cybertron/record/record_writer.h" +#include "cyber/common/log.h" +#include "cyber/proto/record.pb.h" +#include "cyber/record/record_file.h" +#include "cyber/record/record_writer.h" -using ::apollo::cybertron::proto::Header; -using ::apollo::cybertron::proto::ChunkHeader; -using ::apollo::cybertron::proto::ChunkBody; -using ::apollo::cybertron::proto::ChannelCache; +using ::apollo::cyber::proto::Header; +using ::apollo::cyber::proto::ChunkHeader; +using ::apollo::cyber::proto::ChunkBody; +using ::apollo::cyber::proto::ChannelCache; namespace apollo { -namespace cybertron { +namespace cyber { namespace record { class Recoverer { @@ -51,7 +51,7 @@ class Recoverer { }; } // namespace record -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TOOLS_CYBER_RECORDER_RECOVERER_H_ +#endif // CYBER_TOOLS_CYBER_RECORDER_RECOVERER_H_ diff --git a/cybertron/tools/cyber_recorder/spliter.cc b/cyber/tools/cyber_recorder/spliter.cc similarity index 98% rename from cybertron/tools/cyber_recorder/spliter.cc rename to cyber/tools/cyber_recorder/spliter.cc index bec02e2ad8d..3c96991ab69 100644 --- a/cybertron/tools/cyber_recorder/spliter.cc +++ b/cyber/tools/cyber_recorder/spliter.cc @@ -14,10 +14,10 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/tools/cyber_recorder/spliter.h" +#include "cyber/tools/cyber_recorder/spliter.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace record { Spliter::Spliter(const std::string& input_file, const std::string& output_file, @@ -164,5 +164,5 @@ bool Spliter::Proc() { } // end for Proc() } // namespace record -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/tools/cyber_recorder/spliter.h b/cyber/tools/cyber_recorder/spliter.h similarity index 73% rename from cybertron/tools/cyber_recorder/spliter.h rename to cyber/tools/cyber_recorder/spliter.h index d1e487438c8..bc3e2f5beca 100644 --- a/cybertron/tools/cyber_recorder/spliter.h +++ b/cyber/tools/cyber_recorder/spliter.h @@ -14,26 +14,26 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TOOLS_CYBER_RECORDER_SPLITER_H_ -#define CYBERTRON_TOOLS_CYBER_RECORDER_SPLITER_H_ +#ifndef CYBER_TOOLS_CYBER_RECORDER_SPLITER_H_ +#define CYBER_TOOLS_CYBER_RECORDER_SPLITER_H_ #include #include #include #include -#include "cybertron/common/log.h" -#include "cybertron/proto/record.pb.h" -#include "cybertron/record/header_builder.h" -#include "cybertron/record/record_file.h" +#include "cyber/common/log.h" +#include "cyber/proto/record.pb.h" +#include "cyber/record/header_builder.h" +#include "cyber/record/record_file.h" -using ::apollo::cybertron::proto::Header; -using ::apollo::cybertron::proto::ChunkHeader; -using ::apollo::cybertron::proto::ChunkBody; -using ::apollo::cybertron::proto::ChannelCache; +using ::apollo::cyber::proto::Header; +using ::apollo::cyber::proto::ChunkHeader; +using ::apollo::cyber::proto::ChunkBody; +using ::apollo::cyber::proto::ChannelCache; namespace apollo { -namespace cybertron { +namespace cyber { namespace record { class Spliter { @@ -58,7 +58,7 @@ class Spliter { }; } // namespace record -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TOOLS_CYBER_RECORDER_SPLITER_H_ +#endif // CYBER_TOOLS_CYBER_RECORDER_SPLITER_H_ diff --git a/cybertron/tools/cyber_tools_auto_complete.bash b/cyber/tools/cyber_tools_auto_complete.bash similarity index 95% rename from cybertron/tools/cyber_tools_auto_complete.bash rename to cyber/tools/cyber_tools_auto_complete.bash index 10daa79eba9..049379466a1 100644 --- a/cybertron/tools/cyber_tools_auto_complete.bash +++ b/cyber/tools/cyber_tools_auto_complete.bash @@ -11,7 +11,7 @@ function _cyber_launch_complete() { ;; 'start') compopt -o nospace - local files=`cd ${CYBERTRON_PATH}/launch/ 2>/dev/null && ls -l *.launch |awk '{print $NF}' 2>/dev/null` + local files=`cd ${CYBER_PATH}/launch/ 2>/dev/null && ls -l *.launch |awk '{print $NF}' 2>/dev/null` COMPREPLY=( $(compgen -W "$files" -- ${word}) ) #COMPREPLY=( $(compgen -d -f -G "$pattern" -- ${word}) ) ;; diff --git a/cybertron/tools/module_env.bash b/cyber/tools/module_env.bash similarity index 100% rename from cybertron/tools/module_env.bash rename to cyber/tools/module_env.bash diff --git a/cyber/tools/setup.bash b/cyber/tools/setup.bash new file mode 100755 index 00000000000..f9cbe2bc5e1 --- /dev/null +++ b/cyber/tools/setup.bash @@ -0,0 +1,14 @@ +export CYBER_PATH=$(cd "$(dirname "${BASH_SOURCE[0]}")" && pwd) +library_path="${CYBER_PATH}/lib:${CYBER_PATH}/third_party:${CYBER_PATH}/lib/python" +binary_path=${CYBER_PATH}/bin/ +qt_path=${CYBER_PATH}/../third_party/Qt5.5.1/5.5/gcc_64 + +export LD_LIBRARY_PATH=${library_path}:${qt_path}/lib:$LD_LIBRARY_PATH +export QT_QPA_PLATFORM_PLUGIN_PATH=${CYBER_PATH}/third_party/plugins +export PATH=${binary_path}:${qt_path}/bin:$PATH +export PYTHONPATH=${CYBER_PATH}/lib/python:${CYBER_PATH}/lib/python/cyber:${CYBER_PATH}/lib/python/cyber/proto:$PYTHONPATH + +export CYBER_DOMAIN_ID=80 +export CYBER_IP=127.0.0.1 + +source ${CYBER_PATH}/cyber_tools_auto_complete.bash diff --git a/cybertron/transport/BUILD b/cyber/transport/BUILD similarity index 64% rename from cybertron/transport/BUILD rename to cyber/transport/BUILD index 6e228d960e2..7d9e6883252 100644 --- a/cybertron/transport/BUILD +++ b/cyber/transport/BUILD @@ -30,19 +30,19 @@ cc_library( "reactor/*.h", ]), deps = [ - "//cybertron/base:signal", - "//cybertron/common:common", - "//cybertron/message:message_traits", - "//cybertron/message:raw_message", - "//cybertron/proto:qos_profile_cc_proto", - "//cybertron/proto:role_attributes_cc_proto", - "//cybertron/proto:transport_conf_cc_proto", - "//cybertron/service_discovery:role", - "//cybertron/transport/rtps:rtps_lib", - "//cybertron/transport/message:transport_message_lib", - "//cybertron/transport/common:transport_common", - "//cybertron/time:time", - "//cybertron/timer:timer_manager", + "//cyber/base:signal", + "//cyber/common:common", + "//cyber/message:message_traits", + "//cyber/message:raw_message", + "//cyber/proto:qos_profile_cc_proto", + "//cyber/proto:role_attributes_cc_proto", + "//cyber/proto:transport_conf_cc_proto", + "//cyber/service_discovery:role", + "//cyber/transport/rtps:rtps_lib", + "//cyber/transport/message:transport_message_lib", + "//cyber/transport/common:transport_common", + "//cyber/time:time", + "//cyber/timer:timer_manager", ], ) @@ -53,8 +53,8 @@ cc_test( "dispatcher_test.cc", ], deps = [ - "//cybertron:cybertron_core", - "//cybertron/proto:chatter_cc_proto", + "//cyber:cyber_core", + "//cyber/proto:chatter_cc_proto", "@gtest//:main", ], ) @@ -66,8 +66,8 @@ cc_test( "hybrid_transceiver_test.cc", ], deps = [ - "//cybertron:cybertron_core", - "//cybertron/proto:unit_test_cc_proto", + "//cyber:cyber_core", + "//cyber/proto:unit_test_cc_proto", "@gtest", ], ) @@ -79,8 +79,8 @@ cc_test( "intra_dispatcher_test.cc", ], deps = [ - "//cybertron:cybertron_core", - "//cybertron/proto:chatter_cc_proto", + "//cyber:cyber_core", + "//cyber/proto:chatter_cc_proto", "@gtest//:main", ], ) @@ -92,8 +92,8 @@ cc_test( "intra_transceiver_test.cc", ], deps = [ - "//cybertron:cybertron_core", - "//cybertron/proto:unit_test_cc_proto", + "//cyber:cyber_core", + "//cyber/proto:unit_test_cc_proto", "@gtest//:main", ], ) @@ -105,7 +105,7 @@ cc_test( "message_test.cc", ], deps = [ - "//cybertron:cybertron_core", + "//cyber:cyber_core", "@gtest//:main", ], ) @@ -115,7 +115,7 @@ cc_test( size = "small", srcs = [ "reactor/reactor_test.cc", ], deps = [ - "//cybertron:cybertron_core", + "//cyber:cyber_core", "@gtest//:main", ], ) @@ -127,8 +127,8 @@ cc_test( "rtps_dispatcher_test.cc", ], deps = [ - "//cybertron:cybertron_core", - "//cybertron/proto:chatter_cc_proto", + "//cyber:cyber_core", + "//cyber/proto:chatter_cc_proto", "@gtest//:main", ], ) @@ -140,7 +140,7 @@ cc_test( "rtps_test.cc", ], deps = [ - "//cybertron:cybertron_core", + "//cyber:cyber_core", "@gtest//:main", ], ) @@ -152,8 +152,8 @@ cc_test( "rtps_transceiver_test.cc", ], deps = [ - "//cybertron:cybertron_core", - "//cybertron/proto:unit_test_cc_proto", + "//cyber:cyber_core", + "//cyber/proto:unit_test_cc_proto", "@gtest", ], ) @@ -165,8 +165,8 @@ cc_test( "shm_dispatcher_test.cc", ], deps = [ - "//cybertron:cybertron_core", - "//cybertron/proto:chatter_cc_proto", + "//cyber:cyber_core", + "//cyber/proto:chatter_cc_proto", "@gtest//:main", ], ) @@ -178,8 +178,8 @@ cc_test( "shm_transceiver_test.cc", ], deps = [ - "//cybertron:cybertron_core", - "//cybertron/proto:unit_test_cc_proto", + "//cyber:cyber_core", + "//cyber/proto:unit_test_cc_proto", "@gtest//:main", ], ) @@ -191,8 +191,8 @@ cc_test( "transport_test.cc", ], deps = [ - "//cybertron:cybertron_core", - "//cybertron/proto:unit_test_cc_proto", + "//cyber:cyber_core", + "//cyber/proto:unit_test_cc_proto", "@gtest", ], ) diff --git a/cybertron/transport/common/BUILD b/cyber/transport/common/BUILD similarity index 76% rename from cybertron/transport/common/BUILD rename to cyber/transport/common/BUILD index 666af25ad18..6bf62aac6f0 100644 --- a/cybertron/transport/common/BUILD +++ b/cyber/transport/common/BUILD @@ -17,8 +17,8 @@ cc_library( hdrs = [ "endpoint.h", ], deps = [ "identity", - "//cybertron/common:global_data", - "//cybertron/proto:role_attributes_cc_proto", + "//cyber/common:global_data", + "//cyber/proto:role_attributes_cc_proto", ], ) @@ -27,7 +27,7 @@ cc_library( srcs = [ "identity.cc", ], hdrs = [ "identity.h", ], deps = [ - "//cybertron/common:util", + "//cyber/common:util", ], ) @@ -36,8 +36,8 @@ cc_library( srcs = [ "syscall_wrapper.cc", ], hdrs = [ "syscall_wrapper.h", ], deps = [ - "//cybertron:binary", - "//cybertron/common:log", + "//cyber:binary", + "//cyber/common:log", ], ) @@ -48,7 +48,7 @@ cc_test( "common_test.cc", ], deps = [ - "//cybertron:cybertron_core", + "//cyber:cyber_core", "@gtest//:main", ], ) diff --git a/cybertron/transport/common/common_test.cc b/cyber/transport/common/common_test.cc similarity index 91% rename from cybertron/transport/common/common_test.cc rename to cyber/transport/common/common_test.cc index a42d19500b5..40509c3e238 100644 --- a/cybertron/transport/common/common_test.cc +++ b/cyber/transport/common/common_test.cc @@ -20,13 +20,13 @@ #include #include -#include "cybertron/common/global_data.h" -#include "cybertron/transport/common/endpoint.h" -#include "cybertron/transport/common/identity.h" -#include "cybertron/transport/common/syscall_wrapper.h" +#include "cyber/common/global_data.h" +#include "cyber/transport/common/endpoint.h" +#include "cyber/transport/common/identity.h" +#include "cyber/transport/common/syscall_wrapper.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { TEST(IdentityTest, identity_test) { @@ -88,5 +88,5 @@ TEST(SyscallWrapperTest, syscall_wrapper_test) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/transport/common/endpoint.cc b/cyber/transport/common/endpoint.cc similarity index 90% rename from cybertron/transport/common/endpoint.cc rename to cyber/transport/common/endpoint.cc index 8c2ed9dc4b2..4eed5877fdc 100644 --- a/cybertron/transport/common/endpoint.cc +++ b/cyber/transport/common/endpoint.cc @@ -14,11 +14,11 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/transport/common/endpoint.h" -#include "cybertron/common/global_data.h" +#include "cyber/transport/common/endpoint.h" +#include "cyber/common/global_data.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { Endpoint::Endpoint(const RoleAttributes& attr) @@ -37,5 +37,5 @@ Endpoint::Endpoint(const RoleAttributes& attr) Endpoint::~Endpoint() {} } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/transport/common/endpoint.h b/cyber/transport/common/endpoint.h similarity index 81% rename from cybertron/transport/common/endpoint.h rename to cyber/transport/common/endpoint.h index cc2aa86c74c..d9195c058f3 100644 --- a/cybertron/transport/common/endpoint.h +++ b/cyber/transport/common/endpoint.h @@ -14,17 +14,17 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TRANSPORT_COMMON_ENDPOINT_H_ -#define CYBERTRON_TRANSPORT_COMMON_ENDPOINT_H_ +#ifndef CYBER_TRANSPORT_COMMON_ENDPOINT_H_ +#define CYBER_TRANSPORT_COMMON_ENDPOINT_H_ #include #include -#include "cybertron/proto/role_attributes.pb.h" -#include "cybertron/transport/common/identity.h" +#include "cyber/proto/role_attributes.pb.h" +#include "cyber/transport/common/identity.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { class Endpoint; @@ -47,7 +47,7 @@ class Endpoint { }; } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TRANSPORT_COMMON_ENDPOINT_H_ +#endif // CYBER_TRANSPORT_COMMON_ENDPOINT_H_ diff --git a/cybertron/transport/common/identity.cc b/cyber/transport/common/identity.cc similarity index 94% rename from cybertron/transport/common/identity.cc rename to cyber/transport/common/identity.cc index a022e1041a5..2f9617862ce 100644 --- a/cybertron/transport/common/identity.cc +++ b/cyber/transport/common/identity.cc @@ -14,14 +14,14 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/transport/common/identity.h" +#include "cyber/transport/common/identity.h" #include -#include "cybertron/common/util.h" +#include "cyber/common/util.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { Identity::Identity(bool need_generate) : hash_value_(0), hash_value_str_("") { @@ -71,5 +71,5 @@ void Identity::Update() { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/transport/common/identity.h b/cyber/transport/common/identity.h similarity index 89% rename from cybertron/transport/common/identity.h rename to cyber/transport/common/identity.h index 910ab81eec2..89a272221f9 100644 --- a/cybertron/transport/common/identity.h +++ b/cyber/transport/common/identity.h @@ -14,15 +14,15 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TRANSPORT_COMMON_IDENTITY_H_ -#define CYBERTRON_TRANSPORT_COMMON_IDENTITY_H_ +#ifndef CYBER_TRANSPORT_COMMON_IDENTITY_H_ +#define CYBER_TRANSPORT_COMMON_IDENTITY_H_ #include #include #include namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { const uint8_t ID_SIZE = 8; @@ -61,7 +61,7 @@ class Identity { }; } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TRANSPORT_COMMON_IDENTITY_H_ +#endif // CYBER_TRANSPORT_COMMON_IDENTITY_H_ diff --git a/cybertron/transport/common/syscall_wrapper.cc b/cyber/transport/common/syscall_wrapper.cc similarity index 89% rename from cybertron/transport/common/syscall_wrapper.cc rename to cyber/transport/common/syscall_wrapper.cc index 0277ed097c5..e5ca124653a 100644 --- a/cybertron/transport/common/syscall_wrapper.cc +++ b/cyber/transport/common/syscall_wrapper.cc @@ -14,12 +14,12 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/transport/common/syscall_wrapper.h" +#include "cyber/transport/common/syscall_wrapper.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { bool SetNonBlocking(int fd) { @@ -40,5 +40,5 @@ void CloseAndReset(int *fd) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/transport/common/syscall_wrapper.h b/cyber/transport/common/syscall_wrapper.h similarity index 82% rename from cybertron/transport/common/syscall_wrapper.h rename to cyber/transport/common/syscall_wrapper.h index 48e6445efa7..758860c83a2 100644 --- a/cybertron/transport/common/syscall_wrapper.h +++ b/cyber/transport/common/syscall_wrapper.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TRANSPORT_COMMON_SYSCALL_WRAPPER_H_ -#define CYBERTRON_TRANSPORT_COMMON_SYSCALL_WRAPPER_H_ +#ifndef CYBER_TRANSPORT_COMMON_SYSCALL_WRAPPER_H_ +#define CYBER_TRANSPORT_COMMON_SYSCALL_WRAPPER_H_ #include #include @@ -25,7 +25,7 @@ #include namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { bool SetNonBlocking(int fd); @@ -33,7 +33,7 @@ bool SetNonBlocking(int fd); void CloseAndReset(int *fd); } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TRANSPORT_COMMON_SYSCALL_WRAPPER_H_ +#endif // CYBER_TRANSPORT_COMMON_SYSCALL_WRAPPER_H_ diff --git a/cybertron/transport/dispatcher/dispatcher.cc b/cyber/transport/dispatcher/dispatcher.cc similarity index 91% rename from cybertron/transport/dispatcher/dispatcher.cc rename to cyber/transport/dispatcher/dispatcher.cc index 6518ad4badf..c16e8df02a6 100644 --- a/cybertron/transport/dispatcher/dispatcher.cc +++ b/cyber/transport/dispatcher/dispatcher.cc @@ -14,10 +14,10 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/transport/dispatcher/dispatcher.h" +#include "cyber/transport/dispatcher/dispatcher.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { Dispatcher::Dispatcher() : shutdown_(false) {} @@ -31,5 +31,5 @@ bool Dispatcher::HasChannel(uint64_t channel_id) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/transport/dispatcher/dispatcher.h b/cyber/transport/dispatcher/dispatcher.h similarity index 84% rename from cybertron/transport/dispatcher/dispatcher.h rename to cyber/transport/dispatcher/dispatcher.h index c333bb5e196..393d87cbab2 100644 --- a/cybertron/transport/dispatcher/dispatcher.h +++ b/cyber/transport/dispatcher/dispatcher.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TRANSPORT_DISPATCHER_DISPATCHER_H_ -#define CYBERTRON_TRANSPORT_DISPATCHER_DISPATCHER_H_ +#ifndef CYBER_TRANSPORT_DISPATCHER_DISPATCHER_H_ +#define CYBER_TRANSPORT_DISPATCHER_DISPATCHER_H_ #include #include @@ -24,24 +24,24 @@ #include #include -#include "cybertron/base/atomic_hash_map.h" -#include "cybertron/base/atomic_rw_lock.h" -#include "cybertron/common/global_data.h" -#include "cybertron/common/log.h" -#include "cybertron/proto/role_attributes.pb.h" -#include "cybertron/transport/message/listener_handler.h" -#include "cybertron/transport/message/message_info.h" +#include "cyber/base/atomic_hash_map.h" +#include "cyber/base/atomic_rw_lock.h" +#include "cyber/common/global_data.h" +#include "cyber/common/log.h" +#include "cyber/proto/role_attributes.pb.h" +#include "cyber/transport/message/listener_handler.h" +#include "cyber/transport/message/message_info.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { -using apollo::cybertron::base::AtomicHashMap; -using apollo::cybertron::base::AtomicRWLock; -using apollo::cybertron::base::ReadLockGuard; -using apollo::cybertron::base::WriteLockGuard; -using apollo::cybertron::common::GlobalData; -using cybertron::proto::RoleAttributes; +using apollo::cyber::base::AtomicHashMap; +using apollo::cyber::base::AtomicRWLock; +using apollo::cyber::base::ReadLockGuard; +using apollo::cyber::base::WriteLockGuard; +using apollo::cyber::common::GlobalData; +using cyber::proto::RoleAttributes; class Dispatcher; using DispatcherPtr = std::shared_ptr; @@ -143,7 +143,7 @@ void Dispatcher::RemoveListener(const RoleAttributes& self_attr, } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TRANSPORT_DISPATCHER_DISPATCHER_H_ +#endif // CYBER_TRANSPORT_DISPATCHER_DISPATCHER_H_ diff --git a/cybertron/transport/dispatcher/intra_dispatcher.cc b/cyber/transport/dispatcher/intra_dispatcher.cc similarity index 89% rename from cybertron/transport/dispatcher/intra_dispatcher.cc rename to cyber/transport/dispatcher/intra_dispatcher.cc index 230eb742556..22f7330c1cf 100644 --- a/cybertron/transport/dispatcher/intra_dispatcher.cc +++ b/cyber/transport/dispatcher/intra_dispatcher.cc @@ -14,10 +14,10 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/transport/dispatcher/intra_dispatcher.h" +#include "cyber/transport/dispatcher/intra_dispatcher.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { IntraDispatcher::IntraDispatcher() {} @@ -25,5 +25,5 @@ IntraDispatcher::IntraDispatcher() {} IntraDispatcher::~IntraDispatcher() {} } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/transport/dispatcher/intra_dispatcher.h b/cyber/transport/dispatcher/intra_dispatcher.h similarity index 83% rename from cybertron/transport/dispatcher/intra_dispatcher.h rename to cyber/transport/dispatcher/intra_dispatcher.h index 2c633ddbca2..c4908b67f9b 100644 --- a/cybertron/transport/dispatcher/intra_dispatcher.h +++ b/cyber/transport/dispatcher/intra_dispatcher.h @@ -14,21 +14,21 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TRANSPORT_DISPATCHER_INTRA_DISPATCHER_H_ -#define CYBERTRON_TRANSPORT_DISPATCHER_INTRA_DISPATCHER_H_ +#ifndef CYBER_TRANSPORT_DISPATCHER_INTRA_DISPATCHER_H_ +#define CYBER_TRANSPORT_DISPATCHER_INTRA_DISPATCHER_H_ #include #include #include -#include "cybertron/common/global_data.h" -#include "cybertron/common/log.h" -#include "cybertron/common/macros.h" -#include "cybertron/message/raw_message.h" -#include "cybertron/transport/dispatcher/dispatcher.h" +#include "cyber/common/global_data.h" +#include "cyber/common/log.h" +#include "cyber/common/macros.h" +#include "cyber/message/raw_message.h" +#include "cyber/transport/dispatcher/dispatcher.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { class IntraDispatcher; @@ -69,7 +69,7 @@ void IntraDispatcher::OnMessage(uint64_t channel_id, } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TRANSPORT_DISPATCHER_INTRA_DISPATCHER_H_ +#endif // CYBER_TRANSPORT_DISPATCHER_INTRA_DISPATCHER_H_ diff --git a/cybertron/transport/dispatcher/rtps_dispatcher.cc b/cyber/transport/dispatcher/rtps_dispatcher.cc similarity index 94% rename from cybertron/transport/dispatcher/rtps_dispatcher.cc rename to cyber/transport/dispatcher/rtps_dispatcher.cc index f2d2bed733e..5ad9b1f6343 100644 --- a/cybertron/transport/dispatcher/rtps_dispatcher.cc +++ b/cyber/transport/dispatcher/rtps_dispatcher.cc @@ -14,12 +14,12 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/transport/dispatcher/rtps_dispatcher.h" +#include "cyber/transport/dispatcher/rtps_dispatcher.h" -#include "cybertron/transport/transport.h" +#include "cyber/transport/transport.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { RtpsDispatcher::RtpsDispatcher() {} @@ -73,5 +73,5 @@ void RtpsDispatcher::OnMessage(uint64_t channel_id, } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/transport/dispatcher/rtps_dispatcher.h b/cyber/transport/dispatcher/rtps_dispatcher.h similarity index 86% rename from cybertron/transport/dispatcher/rtps_dispatcher.h rename to cyber/transport/dispatcher/rtps_dispatcher.h index feaa630baed..0f7b145b378 100644 --- a/cybertron/transport/dispatcher/rtps_dispatcher.h +++ b/cyber/transport/dispatcher/rtps_dispatcher.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TRANSPORT_DISPATCHER_RTPS_DISPATCHER_H_ -#define CYBERTRON_TRANSPORT_DISPATCHER_RTPS_DISPATCHER_H_ +#ifndef CYBER_TRANSPORT_DISPATCHER_RTPS_DISPATCHER_H_ +#define CYBER_TRANSPORT_DISPATCHER_RTPS_DISPATCHER_H_ #include #include @@ -23,15 +23,15 @@ #include #include -#include "cybertron/common/log.h" -#include "cybertron/common/macros.h" -#include "cybertron/message/message_traits.h" -#include "cybertron/transport/dispatcher/dispatcher.h" -#include "cybertron/transport/rtps/attributes_filler.h" -#include "cybertron/transport/rtps/sub_listener.h" +#include "cyber/common/log.h" +#include "cyber/common/macros.h" +#include "cyber/message/message_traits.h" +#include "cyber/transport/dispatcher/dispatcher.h" +#include "cyber/transport/rtps/attributes_filler.h" +#include "cyber/transport/rtps/sub_listener.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { struct Subscriber { @@ -104,7 +104,7 @@ void RtpsDispatcher::AddListener(const RoleAttributes& self_attr, } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TRANSPORT_DISPATCHER_RTPS_DISPATCHER_H_ +#endif // CYBER_TRANSPORT_DISPATCHER_RTPS_DISPATCHER_H_ diff --git a/cybertron/transport/dispatcher/shm_dispatcher.cc b/cyber/transport/dispatcher/shm_dispatcher.cc similarity index 94% rename from cybertron/transport/dispatcher/shm_dispatcher.cc rename to cyber/transport/dispatcher/shm_dispatcher.cc index 4e807f917c0..d65425ee0a3 100644 --- a/cybertron/transport/dispatcher/shm_dispatcher.cc +++ b/cyber/transport/dispatcher/shm_dispatcher.cc @@ -14,15 +14,15 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/transport/dispatcher/shm_dispatcher.h" -#include "cybertron/common/global_data.h" -#include "cybertron/common/util.h" -#include "cybertron/transport/shm/readable_info.h" +#include "cyber/transport/dispatcher/shm_dispatcher.h" +#include "cyber/common/global_data.h" +#include "cyber/common/util.h" +#include "cyber/transport/shm/readable_info.h" -using apollo::cybertron::common::GlobalData; +using apollo::cyber::common::GlobalData; namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { ShmDispatcher::ShmDispatcher() : host_id_(0), sfd_(-1) { Init(); } @@ -164,5 +164,5 @@ bool ShmDispatcher::InitMulticast() { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/transport/dispatcher/shm_dispatcher.h b/cyber/transport/dispatcher/shm_dispatcher.h similarity index 83% rename from cybertron/transport/dispatcher/shm_dispatcher.h rename to cyber/transport/dispatcher/shm_dispatcher.h index b5870547b47..62664269ca2 100644 --- a/cybertron/transport/dispatcher/shm_dispatcher.h +++ b/cyber/transport/dispatcher/shm_dispatcher.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TRANSPORT_DISPATCHER_SHM_DISPATCHER_H_ -#define CYBERTRON_TRANSPORT_DISPATCHER_SHM_DISPATCHER_H_ +#ifndef CYBER_TRANSPORT_DISPATCHER_SHM_DISPATCHER_H_ +#define CYBER_TRANSPORT_DISPATCHER_SHM_DISPATCHER_H_ #include #include @@ -29,25 +29,25 @@ #include #include -#include "cybertron/base/atomic_rw_lock.h" -#include "cybertron/common/global_data.h" -#include "cybertron/common/log.h" -#include "cybertron/common/macros.h" -#include "cybertron/message/message_traits.h" -#include "cybertron/proto/transport_conf.pb.h" -#include "cybertron/transport/common/syscall_wrapper.h" -#include "cybertron/transport/dispatcher/dispatcher.h" -#include "cybertron/transport/shm/segment.h" +#include "cyber/base/atomic_rw_lock.h" +#include "cyber/common/global_data.h" +#include "cyber/common/log.h" +#include "cyber/common/macros.h" +#include "cyber/message/message_traits.h" +#include "cyber/proto/transport_conf.pb.h" +#include "cyber/transport/common/syscall_wrapper.h" +#include "cyber/transport/dispatcher/dispatcher.h" +#include "cyber/transport/shm/segment.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { class ShmDispatcher; using ShmDispatcherPtr = std::shared_ptr; -using apollo::cybertron::base::AtomicRWLock; -using apollo::cybertron::base::ReadLockGuard; -using apollo::cybertron::base::WriteLockGuard; +using apollo::cyber::base::AtomicRWLock; +using apollo::cyber::base::ReadLockGuard; +using apollo::cyber::base::WriteLockGuard; class ShmDispatcher : public Dispatcher { public: @@ -132,7 +132,7 @@ void ShmDispatcher::AddListener(const RoleAttributes& self_attr, } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TRANSPORT_DISPATCHER_SHM_DISPATCHER_H_ +#endif // CYBER_TRANSPORT_DISPATCHER_SHM_DISPATCHER_H_ diff --git a/cybertron/transport/dispatcher_test.cc b/cyber/transport/dispatcher_test.cc similarity index 94% rename from cybertron/transport/dispatcher_test.cc rename to cyber/transport/dispatcher_test.cc index 8058c3b365f..c22a37916b4 100644 --- a/cybertron/transport/dispatcher_test.cc +++ b/cyber/transport/dispatcher_test.cc @@ -18,13 +18,13 @@ #include #include -#include "cybertron/common/util.h" -#include "cybertron/proto/chatter.pb.h" -#include "cybertron/transport/common/identity.h" -#include "cybertron/transport/dispatcher/dispatcher.h" +#include "cyber/common/util.h" +#include "cyber/proto/chatter.pb.h" +#include "cyber/transport/common/identity.h" +#include "cyber/transport/dispatcher/dispatcher.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { class DispatcherTest : public ::testing::Test { @@ -130,5 +130,5 @@ TEST_F(DispatcherTest, has_channel) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/transport/hybrid_transceiver_test.cc b/cyber/transport/hybrid_transceiver_test.cc similarity index 96% rename from cybertron/transport/hybrid_transceiver_test.cc rename to cyber/transport/hybrid_transceiver_test.cc index f7b20575b2e..a317f5f1faa 100644 --- a/cybertron/transport/hybrid_transceiver_test.cc +++ b/cyber/transport/hybrid_transceiver_test.cc @@ -20,16 +20,16 @@ #include #include -#include "cybertron/common/global_data.h" -#include "cybertron/common/util.h" -#include "cybertron/proto/unit_test.pb.h" -#include "cybertron/transport/qos/qos_profile_conf.h" -#include "cybertron/transport/receiver/hybrid_receiver.h" -#include "cybertron/transport/transmitter/hybrid_transmitter.h" -#include "cybertron/transport/transport.h" +#include "cyber/common/global_data.h" +#include "cyber/common/util.h" +#include "cyber/proto/unit_test.pb.h" +#include "cyber/transport/qos/qos_profile_conf.h" +#include "cyber/transport/receiver/hybrid_receiver.h" +#include "cyber/transport/transmitter/hybrid_transmitter.h" +#include "cyber/transport/transport.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { class HybridTransceiverTest : public ::testing::Test { @@ -395,12 +395,12 @@ TEST_F(HybridTransceiverTest, enable_and_disable_with_param_diff_host) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { testing::InitGoogleTest(&argc, argv); auto res = RUN_ALL_TESTS(); - apollo::cybertron::transport::Transport::Shutdown(); + apollo::cyber::transport::Transport::Shutdown(); return res; } diff --git a/cybertron/transport/intra_dispatcher_test.cc b/cyber/transport/intra_dispatcher_test.cc similarity index 91% rename from cybertron/transport/intra_dispatcher_test.cc rename to cyber/transport/intra_dispatcher_test.cc index 8cd9117946d..3ad89af4233 100644 --- a/cybertron/transport/intra_dispatcher_test.cc +++ b/cyber/transport/intra_dispatcher_test.cc @@ -17,14 +17,14 @@ #include #include -#include "cybertron/common/util.h" -#include "cybertron/message/raw_message.h" -#include "cybertron/proto/chatter.pb.h" -#include "cybertron/transport/common/identity.h" -#include "cybertron/transport/dispatcher/intra_dispatcher.h" +#include "cyber/common/util.h" +#include "cyber/message/raw_message.h" +#include "cyber/proto/chatter.pb.h" +#include "cyber/transport/common/identity.h" +#include "cyber/transport/dispatcher/intra_dispatcher.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { TEST(IntraDispatcherTest, constructor) { @@ -82,5 +82,5 @@ TEST(IntraDispatcherTest, on_message) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/transport/intra_transceiver_test.cc b/cyber/transport/intra_transceiver_test.cc similarity index 95% rename from cybertron/transport/intra_transceiver_test.cc rename to cyber/transport/intra_transceiver_test.cc index 4d577795411..f71b0385a3f 100644 --- a/cybertron/transport/intra_transceiver_test.cc +++ b/cyber/transport/intra_transceiver_test.cc @@ -19,12 +19,12 @@ #include #include -#include "cybertron/proto/unit_test.pb.h" -#include "cybertron/transport/receiver/intra_receiver.h" -#include "cybertron/transport/transmitter/intra_transmitter.h" +#include "cyber/proto/unit_test.pb.h" +#include "cyber/transport/receiver/intra_receiver.h" +#include "cyber/transport/transmitter/intra_transmitter.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { class IntraTranceiverTest : public ::testing::Test { @@ -136,5 +136,5 @@ TEST_F(IntraTranceiverTest, enable_and_disable) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/transport/message/BUILD b/cyber/transport/message/BUILD similarity index 60% rename from cybertron/transport/message/BUILD rename to cyber/transport/message/BUILD index 2db760533f5..cfb3866c42d 100644 --- a/cybertron/transport/message/BUILD +++ b/cyber/transport/message/BUILD @@ -11,10 +11,10 @@ cc_library( "*.h", ]), deps = [ - "//cybertron/base:signal", - "//cybertron/common:common", - "//cybertron/message:raw_message", - "//cybertron/transport/common:transport_common", + "//cyber/base:signal", + "//cyber/common:common", + "//cyber/message:raw_message", + "//cyber/transport/common:transport_common", ], ) diff --git a/cybertron/transport/message/history.h b/cyber/transport/message/history.h similarity index 91% rename from cybertron/transport/message/history.h rename to cyber/transport/message/history.h index a1d99638afe..ca0a89b0ea5 100644 --- a/cybertron/transport/message/history.h +++ b/cyber/transport/message/history.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TRANSPORT_MESSAGE_HISTORY_H_ -#define CYBERTRON_TRANSPORT_MESSAGE_HISTORY_H_ +#ifndef CYBER_TRANSPORT_MESSAGE_HISTORY_H_ +#define CYBER_TRANSPORT_MESSAGE_HISTORY_H_ #include #include @@ -23,12 +23,12 @@ #include #include -#include "cybertron/common/global_data.h" -#include "cybertron/transport/message/history_attributes.h" -#include "cybertron/transport/message/message_info.h" +#include "cyber/common/global_data.h" +#include "cyber/transport/message/history_attributes.h" +#include "cyber/transport/message/message_info.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { template @@ -140,7 +140,7 @@ size_t History::GetSize() { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TRANSPORT_MESSAGE_HISTORY_H_ +#endif // CYBER_TRANSPORT_MESSAGE_HISTORY_H_ diff --git a/cybertron/transport/message/history_attributes.h b/cyber/transport/message/history_attributes.h similarity index 82% rename from cybertron/transport/message/history_attributes.h rename to cyber/transport/message/history_attributes.h index c4b77eeca29..a4954799e8a 100644 --- a/cybertron/transport/message/history_attributes.h +++ b/cyber/transport/message/history_attributes.h @@ -14,15 +14,15 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TRANSPORT_MESSAGE_HISTORY_ATTRIBUTES_H_ -#define CYBERTRON_TRANSPORT_MESSAGE_HISTORY_ATTRIBUTES_H_ +#ifndef CYBER_TRANSPORT_MESSAGE_HISTORY_ATTRIBUTES_H_ +#define CYBER_TRANSPORT_MESSAGE_HISTORY_ATTRIBUTES_H_ #include -#include "cybertron/proto/qos_profile.pb.h" +#include "cyber/proto/qos_profile.pb.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { struct HistoryAttributes { @@ -38,7 +38,7 @@ struct HistoryAttributes { }; } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TRANSPORT_MESSAGE_HISTORY_ATTRIBUTES_H_ +#endif // CYBER_TRANSPORT_MESSAGE_HISTORY_ATTRIBUTES_H_ diff --git a/cybertron/transport/message/listener_handler.h b/cyber/transport/message/listener_handler.h similarity index 89% rename from cybertron/transport/message/listener_handler.h rename to cyber/transport/message/listener_handler.h index 7f15f0c524d..1a54e22cb10 100644 --- a/cybertron/transport/message/listener_handler.h +++ b/cyber/transport/message/listener_handler.h @@ -14,26 +14,26 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TRANSPORT_MESSAGE_LISTENER_HANDLER_H_ -#define CYBERTRON_TRANSPORT_MESSAGE_LISTENER_HANDLER_H_ +#ifndef CYBER_TRANSPORT_MESSAGE_LISTENER_HANDLER_H_ +#define CYBER_TRANSPORT_MESSAGE_LISTENER_HANDLER_H_ #include #include #include #include -#include "cybertron/base/atomic_rw_lock.h" -#include "cybertron/base/signal.h" -#include "cybertron/message/raw_message.h" -#include "cybertron/transport/message/message_info.h" +#include "cyber/base/atomic_rw_lock.h" +#include "cyber/base/signal.h" +#include "cyber/message/raw_message.h" +#include "cyber/transport/message/message_info.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { -using apollo::cybertron::base::AtomicRWLock; -using apollo::cybertron::base::ReadLockGuard; -using apollo::cybertron::base::WriteLockGuard; +using apollo::cyber::base::AtomicRWLock; +using apollo::cyber::base::ReadLockGuard; +using apollo::cyber::base::WriteLockGuard; class ListenerHandlerBase; using ListenerHandlerBasePtr = std::shared_ptr; @@ -158,7 +158,7 @@ void ListenerHandler::Run(const Message& msg, } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TRANSPORT_MESSAGE_LISTENER_HANDLER_H_ +#endif // CYBER_TRANSPORT_MESSAGE_LISTENER_HANDLER_H_ diff --git a/cybertron/transport/message/message_info.cc b/cyber/transport/message/message_info.cc similarity index 96% rename from cybertron/transport/message/message_info.cc rename to cyber/transport/message/message_info.cc index e75f2e7566f..ff44fb1a562 100644 --- a/cybertron/transport/message/message_info.cc +++ b/cyber/transport/message/message_info.cc @@ -14,14 +14,14 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/transport/message/message_info.h" +#include "cyber/transport/message/message_info.h" #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { MessageInfo::MessageInfo() : sender_id_(false), seq_num_(0), spare_id_(false) {} @@ -129,5 +129,5 @@ bool MessageInfo::DeserializeFrom(const std::string& src) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/transport/message/message_info.h b/cyber/transport/message/message_info.h similarity index 87% rename from cybertron/transport/message/message_info.h rename to cyber/transport/message/message_info.h index 7f4cc435458..fa63c80ebe7 100644 --- a/cybertron/transport/message/message_info.h +++ b/cyber/transport/message/message_info.h @@ -14,16 +14,16 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TRANSPORT_MESSAGE_MESSAGE_INFO_H_ -#define CYBERTRON_TRANSPORT_MESSAGE_MESSAGE_INFO_H_ +#ifndef CYBER_TRANSPORT_MESSAGE_MESSAGE_INFO_H_ +#define CYBER_TRANSPORT_MESSAGE_MESSAGE_INFO_H_ #include #include -#include "cybertron/transport/common/identity.h" +#include "cyber/transport/common/identity.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { class MessageInfo { @@ -58,7 +58,7 @@ class MessageInfo { }; } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TRANSPORT_MESSAGE_MESSAGE_INFO_H_ +#endif // CYBER_TRANSPORT_MESSAGE_MESSAGE_INFO_H_ diff --git a/cybertron/transport/message_test.cc b/cyber/transport/message_test.cc similarity index 93% rename from cybertron/transport/message_test.cc rename to cyber/transport/message_test.cc index a604dad3bb8..fb6d1ba7c7f 100644 --- a/cybertron/transport/message_test.cc +++ b/cyber/transport/message_test.cc @@ -19,18 +19,18 @@ #include #include -#include "cybertron/common/global_data.h" -#include "cybertron/message/raw_message.h" -#include "cybertron/transport/message/history.h" -#include "cybertron/transport/message/history_attributes.h" -#include "cybertron/transport/message/listener_handler.h" -#include "cybertron/transport/message/message_info.h" +#include "cyber/common/global_data.h" +#include "cyber/message/raw_message.h" +#include "cyber/transport/message/history.h" +#include "cyber/transport/message/history_attributes.h" +#include "cyber/transport/message/listener_handler.h" +#include "cyber/transport/message/message_info.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { -using apollo::cybertron::message::RawMessage; +using apollo::cyber::message::RawMessage; TEST(MessageInfoTest, message_info_test) { Identity sender_id; @@ -165,5 +165,5 @@ TEST(ListenerHandlerTest, listener_handler_test) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/transport/qos/BUILD b/cyber/transport/qos/BUILD similarity index 83% rename from cybertron/transport/qos/BUILD rename to cyber/transport/qos/BUILD index 46585fdff13..91a4575882a 100644 --- a/cybertron/transport/qos/BUILD +++ b/cyber/transport/qos/BUILD @@ -11,7 +11,7 @@ cc_library( "*.h", ]), deps = [ - "//cybertron/proto:qos_profile_cc_proto", + "//cyber/proto:qos_profile_cc_proto", ], ) diff --git a/cybertron/transport/qos/qos_profile_conf.cc b/cyber/transport/qos/qos_profile_conf.cc similarity index 97% rename from cybertron/transport/qos/qos_profile_conf.cc rename to cyber/transport/qos/qos_profile_conf.cc index dbd7290c692..0c45d8a5861 100644 --- a/cybertron/transport/qos/qos_profile_conf.cc +++ b/cyber/transport/qos/qos_profile_conf.cc @@ -14,10 +14,10 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/transport/qos/qos_profile_conf.h" +#include "cyber/transport/qos/qos_profile_conf.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { QosProfileConf::QosProfileConf() {} @@ -83,5 +83,5 @@ const QosProfile QosProfileConf::QOS_PROFILE_TOPO_CHANGE = CreateQosProfile( QosDurabilityPolicy::DURABILITY_TRANSIENT_LOCAL); } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/transport/qos/qos_profile_conf.h b/cyber/transport/qos/qos_profile_conf.h similarity index 80% rename from cybertron/transport/qos/qos_profile_conf.h rename to cyber/transport/qos/qos_profile_conf.h index ff38c09c3cb..b58580aba8c 100644 --- a/cybertron/transport/qos/qos_profile_conf.h +++ b/cyber/transport/qos/qos_profile_conf.h @@ -14,21 +14,21 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TRANSPORT_QOS_QOS_PROFILE_CONF_H_ -#define CYBERTRON_TRANSPORT_QOS_QOS_PROFILE_CONF_H_ +#ifndef CYBER_TRANSPORT_QOS_QOS_PROFILE_CONF_H_ +#define CYBER_TRANSPORT_QOS_QOS_PROFILE_CONF_H_ #include -#include "cybertron/proto/qos_profile.pb.h" +#include "cyber/proto/qos_profile.pb.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { -using cybertron::proto::QosDurabilityPolicy; -using cybertron::proto::QosHistoryPolicy; -using cybertron::proto::QosProfile; -using cybertron::proto::QosReliabilityPolicy; +using cyber::proto::QosDurabilityPolicy; +using cyber::proto::QosHistoryPolicy; +using cyber::proto::QosProfile; +using cyber::proto::QosReliabilityPolicy; class QosProfileConf { public: @@ -54,7 +54,7 @@ class QosProfileConf { }; } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TRANSPORT_QOS_QOS_PROFILE_CONF_H_ +#endif // CYBER_TRANSPORT_QOS_QOS_PROFILE_CONF_H_ diff --git a/cybertron/transport/reactor/reactor.cc b/cyber/transport/reactor/reactor.cc similarity index 97% rename from cybertron/transport/reactor/reactor.cc rename to cyber/transport/reactor/reactor.cc index 93e7ed9503f..c21821af4bf 100644 --- a/cybertron/transport/reactor/reactor.cc +++ b/cyber/transport/reactor/reactor.cc @@ -14,18 +14,18 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/transport/reactor/reactor.h" +#include "cyber/transport/reactor/reactor.h" #include #include #include #include -#include "cybertron/common/log.h" -#include "cybertron/transport/common/syscall_wrapper.h" +#include "cyber/common/log.h" +#include "cyber/transport/common/syscall_wrapper.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { Reactor::Reactor() : shutdown_(true), epoll_fd_(INVALID_FD), changed_(false) { @@ -271,5 +271,5 @@ bool Reactor::CreatePipe() { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/transport/reactor/reactor.h b/cyber/transport/reactor/reactor.h similarity index 90% rename from cybertron/transport/reactor/reactor.h rename to cyber/transport/reactor/reactor.h index 98e660d05c8..0df2a18d1b5 100644 --- a/cybertron/transport/reactor/reactor.h +++ b/cyber/transport/reactor/reactor.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TRANSPORT_REACTOR_REACTOR_H_ -#define CYBERTRON_TRANSPORT_REACTOR_REACTOR_H_ +#ifndef CYBER_TRANSPORT_REACTOR_REACTOR_H_ +#define CYBER_TRANSPORT_REACTOR_REACTOR_H_ #include #include @@ -24,10 +24,10 @@ #include #include -#include "cybertron/common/macros.h" +#include "cyber/common/macros.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { using Handle = int; @@ -85,7 +85,7 @@ class Reactor { }; } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TRANSPORT_REACTOR_REACTOR_H_ +#endif // CYBER_TRANSPORT_REACTOR_REACTOR_H_ diff --git a/cybertron/transport/reactor/reactor_test.cc b/cyber/transport/reactor/reactor_test.cc similarity index 93% rename from cybertron/transport/reactor/reactor_test.cc rename to cyber/transport/reactor/reactor_test.cc index b7f8ccf02e0..14887e947b5 100644 --- a/cybertron/transport/reactor/reactor_test.cc +++ b/cyber/transport/reactor/reactor_test.cc @@ -19,12 +19,12 @@ #include #include -#include "cybertron/common/log.h" -#include "cybertron/transport/common/syscall_wrapper.h" -#include "cybertron/transport/reactor/reactor.h" +#include "cyber/common/log.h" +#include "cyber/transport/common/syscall_wrapper.h" +#include "cyber/transport/reactor/reactor.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { TEST(ReactorTest, constructor) { @@ -94,5 +94,5 @@ TEST(ReactorTest, shutdown) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/transport/receiver/hybrid_receiver.h b/cyber/transport/receiver/hybrid_receiver.h similarity index 90% rename from cybertron/transport/receiver/hybrid_receiver.h rename to cyber/transport/receiver/hybrid_receiver.h index 498bb60a944..e7a853b0bcd 100644 --- a/cybertron/transport/receiver/hybrid_receiver.h +++ b/cyber/transport/receiver/hybrid_receiver.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TRANSPORT_RECEIVER_HYBRID_RECEIVER_H_ -#define CYBERTRON_TRANSPORT_RECEIVER_HYBRID_RECEIVER_H_ +#ifndef CYBER_TRANSPORT_RECEIVER_HYBRID_RECEIVER_H_ +#define CYBER_TRANSPORT_RECEIVER_HYBRID_RECEIVER_H_ #include #include @@ -26,25 +26,25 @@ #include #include -#include "cybertron/common/global_data.h" -#include "cybertron/common/log.h" -#include "cybertron/common/types.h" -#include "cybertron/proto/role_attributes.pb.h" -#include "cybertron/service_discovery/role/role.h" -#include "cybertron/time/time.h" -#include "cybertron/timer/timer_manager.h" -#include "cybertron/transport/receiver/intra_receiver.h" -#include "cybertron/transport/receiver/rtps_receiver.h" -#include "cybertron/transport/receiver/shm_receiver.h" -#include "cybertron/transport/rtps/participant.h" +#include "cyber/common/global_data.h" +#include "cyber/common/log.h" +#include "cyber/common/types.h" +#include "cyber/proto/role_attributes.pb.h" +#include "cyber/service_discovery/role/role.h" +#include "cyber/time/time.h" +#include "cyber/timer/timer_manager.h" +#include "cyber/transport/receiver/intra_receiver.h" +#include "cyber/transport/receiver/rtps_receiver.h" +#include "cyber/transport/receiver/shm_receiver.h" +#include "cyber/transport/rtps/participant.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { -using apollo::cybertron::proto::OptionalMode; -using apollo::cybertron::proto::QosDurabilityPolicy; -using apollo::cybertron::proto::RoleAttributes; +using apollo::cyber::proto::OptionalMode; +using apollo::cyber::proto::QosDurabilityPolicy; +using apollo::cyber::proto::RoleAttributes; template class HybridReceiver : public Receiver { @@ -296,7 +296,7 @@ Relation HybridReceiver::GetRelation(const RoleAttributes& opposite_attr) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TRANSPORT_RECEIVER_HYBRID_RECEIVER_H_ +#endif // CYBER_TRANSPORT_RECEIVER_HYBRID_RECEIVER_H_ diff --git a/cybertron/transport/receiver/intra_receiver.h b/cyber/transport/receiver/intra_receiver.h similarity index 87% rename from cybertron/transport/receiver/intra_receiver.h rename to cyber/transport/receiver/intra_receiver.h index e04d225e41c..23dd0912638 100644 --- a/cybertron/transport/receiver/intra_receiver.h +++ b/cyber/transport/receiver/intra_receiver.h @@ -14,15 +14,15 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TRANSPORT_RECEIVER_INTRA_RECEIVER_H_ -#define CYBERTRON_TRANSPORT_RECEIVER_INTRA_RECEIVER_H_ +#ifndef CYBER_TRANSPORT_RECEIVER_INTRA_RECEIVER_H_ +#define CYBER_TRANSPORT_RECEIVER_INTRA_RECEIVER_H_ -#include "cybertron/common/log.h" -#include "cybertron/transport/dispatcher/intra_dispatcher.h" -#include "cybertron/transport/receiver/receiver.h" +#include "cyber/common/log.h" +#include "cyber/transport/dispatcher/intra_dispatcher.h" +#include "cyber/transport/receiver/receiver.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { template @@ -89,7 +89,7 @@ void IntraReceiver::Disable(const RoleAttributes& opposite_attr) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TRANSPORT_RECEIVER_INTRA_RECEIVER_H_ +#endif // CYBER_TRANSPORT_RECEIVER_INTRA_RECEIVER_H_ diff --git a/cybertron/transport/receiver/receiver.h b/cyber/transport/receiver/receiver.h similarity index 85% rename from cybertron/transport/receiver/receiver.h rename to cyber/transport/receiver/receiver.h index e7079d9c005..b8f5438b090 100644 --- a/cybertron/transport/receiver/receiver.h +++ b/cyber/transport/receiver/receiver.h @@ -14,18 +14,18 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TRANSPORT_RECEIVER_RECEIVER_H_ -#define CYBERTRON_TRANSPORT_RECEIVER_RECEIVER_H_ +#ifndef CYBER_TRANSPORT_RECEIVER_RECEIVER_H_ +#define CYBER_TRANSPORT_RECEIVER_RECEIVER_H_ #include #include -#include "cybertron/transport/common/endpoint.h" -#include "cybertron/transport/message/history.h" -#include "cybertron/transport/message/message_info.h" +#include "cyber/transport/common/endpoint.h" +#include "cyber/transport/message/history.h" +#include "cyber/transport/message/message_info.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { template @@ -66,7 +66,7 @@ void Receiver::OnNewMessage(const MessagePtr& msg, } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TRANSPORT_RECEIVER_RECEIVER_H_ +#endif // CYBER_TRANSPORT_RECEIVER_RECEIVER_H_ diff --git a/cybertron/transport/receiver/rtps_receiver.h b/cyber/transport/receiver/rtps_receiver.h similarity index 87% rename from cybertron/transport/receiver/rtps_receiver.h rename to cyber/transport/receiver/rtps_receiver.h index 1277a2e74b7..0cc05b48fc7 100644 --- a/cybertron/transport/receiver/rtps_receiver.h +++ b/cyber/transport/receiver/rtps_receiver.h @@ -14,15 +14,15 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TRANSPORT_RECEIVER_RTPS_RECEIVER_H_ -#define CYBERTRON_TRANSPORT_RECEIVER_RTPS_RECEIVER_H_ +#ifndef CYBER_TRANSPORT_RECEIVER_RTPS_RECEIVER_H_ +#define CYBER_TRANSPORT_RECEIVER_RTPS_RECEIVER_H_ -#include "cybertron/common/log.h" -#include "cybertron/transport/dispatcher/rtps_dispatcher.h" -#include "cybertron/transport/receiver/receiver.h" +#include "cyber/common/log.h" +#include "cyber/transport/dispatcher/rtps_dispatcher.h" +#include "cyber/transport/receiver/receiver.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { template @@ -89,7 +89,7 @@ void RtpsReceiver::Disable(const RoleAttributes& opposite_attr) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TRANSPORT_RECEIVER_RTPS_RECEIVER_H_ +#endif // CYBER_TRANSPORT_RECEIVER_RTPS_RECEIVER_H_ diff --git a/cybertron/transport/receiver/shm_receiver.h b/cyber/transport/receiver/shm_receiver.h similarity index 87% rename from cybertron/transport/receiver/shm_receiver.h rename to cyber/transport/receiver/shm_receiver.h index 77f80f57264..21a22e01dd6 100644 --- a/cybertron/transport/receiver/shm_receiver.h +++ b/cyber/transport/receiver/shm_receiver.h @@ -14,17 +14,17 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TRANSPORT_RECEIVER_SHM_RECEIVER_H_ -#define CYBERTRON_TRANSPORT_RECEIVER_SHM_RECEIVER_H_ +#ifndef CYBER_TRANSPORT_RECEIVER_SHM_RECEIVER_H_ +#define CYBER_TRANSPORT_RECEIVER_SHM_RECEIVER_H_ #include -#include "cybertron/common/log.h" -#include "cybertron/transport/dispatcher/shm_dispatcher.h" -#include "cybertron/transport/receiver/receiver.h" +#include "cyber/common/log.h" +#include "cyber/transport/dispatcher/shm_dispatcher.h" +#include "cyber/transport/receiver/receiver.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { template @@ -91,7 +91,7 @@ void ShmReceiver::Disable(const RoleAttributes& opposite_attr) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TRANSPORT_RECEIVER_SHM_RECEIVER_H_ +#endif // CYBER_TRANSPORT_RECEIVER_SHM_RECEIVER_H_ diff --git a/cyber/transport/rtps/BUILD b/cyber/transport/rtps/BUILD new file mode 100644 index 00000000000..f275f3f79ec --- /dev/null +++ b/cyber/transport/rtps/BUILD @@ -0,0 +1,26 @@ +load("//tools:cpplint.bzl", "cpplint") + +package(default_visibility = ["//visibility:public"]) + +cc_library( + name = "rtps_lib", + srcs = glob([ + "*.cc", + ]), + hdrs = glob([ + "*.h", + ]), + deps = [ + "//cyber/common", + "//cyber/base:atomic_hash_map", + "//cyber/base:atomic_rw_lock", + "//cyber/proto:qos_profile_cc_proto", + "//cyber/proto:transport_conf_cc_proto", + "//cyber/transport/common:transport_common", + "//cyber/transport/message:transport_message_lib", + "//cyber/transport/qos:qos_lib", + "@fastrtps//:fastrtps", + ], +) + +cpplint() diff --git a/cybertron/transport/rtps/attributes_filler.cc b/cyber/transport/rtps/attributes_filler.cc similarity index 96% rename from cybertron/transport/rtps/attributes_filler.cc rename to cyber/transport/rtps/attributes_filler.cc index 69410db55fe..c3786ad9b81 100644 --- a/cybertron/transport/rtps/attributes_filler.cc +++ b/cyber/transport/rtps/attributes_filler.cc @@ -14,15 +14,15 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/transport/rtps/attributes_filler.h" +#include "cyber/transport/rtps/attributes_filler.h" #include -#include "cybertron/common/log.h" -#include "cybertron/transport/qos/qos_profile_conf.h" +#include "cyber/common/log.h" +#include "cyber/transport/qos/qos_profile_conf.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { AttributesFiller::AttributesFiller() {} @@ -178,5 +178,5 @@ bool AttributesFiller::FillInSubAttr( } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/transport/rtps/attributes_filler.h b/cyber/transport/rtps/attributes_filler.h similarity index 86% rename from cybertron/transport/rtps/attributes_filler.h rename to cyber/transport/rtps/attributes_filler.h index 1b2511bfa71..44ab1357031 100644 --- a/cybertron/transport/rtps/attributes_filler.h +++ b/cyber/transport/rtps/attributes_filler.h @@ -14,17 +14,17 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TRANSPORT_RTPS_ATTRIBUTES_FILLER_H_ -#define CYBERTRON_TRANSPORT_RTPS_ATTRIBUTES_FILLER_H_ +#ifndef CYBER_TRANSPORT_RTPS_ATTRIBUTES_FILLER_H_ +#define CYBER_TRANSPORT_RTPS_ATTRIBUTES_FILLER_H_ #include -#include "cybertron/proto/qos_profile.pb.h" +#include "cyber/proto/qos_profile.pb.h" #include "fastrtps/attributes/PublisherAttributes.h" #include "fastrtps/attributes/SubscriberAttributes.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { using proto::QosDurabilityPolicy; @@ -47,7 +47,7 @@ class AttributesFiller { }; } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TRANSPORT_RTPS_ATTRIBUTES_FILLER_H_ +#endif // CYBER_TRANSPORT_RTPS_ATTRIBUTES_FILLER_H_ diff --git a/cybertron/transport/rtps/participant.cc b/cyber/transport/rtps/participant.cc similarity index 95% rename from cybertron/transport/rtps/participant.cc rename to cyber/transport/rtps/participant.cc index d47be4b99cc..35f1ded3b13 100644 --- a/cybertron/transport/rtps/participant.cc +++ b/cyber/transport/rtps/participant.cc @@ -14,14 +14,14 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/transport/rtps/participant.h" +#include "cyber/transport/rtps/participant.h" -#include "cybertron/common/global_data.h" -#include "cybertron/common/log.h" -#include "cybertron/proto/transport_conf.pb.h" +#include "cyber/common/global_data.h" +#include "cyber/common/log.h" +#include "cyber/proto/transport_conf.pb.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { Participant::Participant(const std::string& name, int send_port, @@ -129,5 +129,5 @@ void Participant::CreateFastRtpsParticipant( } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/transport/rtps/participant.h b/cyber/transport/rtps/participant.h similarity index 88% rename from cybertron/transport/rtps/participant.h rename to cyber/transport/rtps/participant.h index 0a6a1299f61..455c897dd33 100644 --- a/cybertron/transport/rtps/participant.h +++ b/cyber/transport/rtps/participant.h @@ -14,15 +14,15 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TRANSPORT_RTPS_PARTICIPANT_H_ -#define CYBERTRON_TRANSPORT_RTPS_PARTICIPANT_H_ +#ifndef CYBER_TRANSPORT_RTPS_PARTICIPANT_H_ +#define CYBER_TRANSPORT_RTPS_PARTICIPANT_H_ #include #include #include #include -#include "cybertron/transport/rtps/underlay_message_type.h" +#include "cyber/transport/rtps/underlay_message_type.h" #include "fastrtps/Domain.h" #include "fastrtps/attributes/ParticipantAttributes.h" #include "fastrtps/participant/Participant.h" @@ -30,7 +30,7 @@ #include "fastrtps/rtps/common/Locator.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { class Participant; @@ -62,7 +62,7 @@ class Participant { }; } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TRANSPORT_RTPS_PARTICIPANT_H_ +#endif // CYBER_TRANSPORT_RTPS_PARTICIPANT_H_ diff --git a/cybertron/transport/rtps/sub_listener.cc b/cyber/transport/rtps/sub_listener.cc similarity index 93% rename from cybertron/transport/rtps/sub_listener.cc rename to cyber/transport/rtps/sub_listener.cc index 0aeb71e8e8b..e623f5b69ba 100644 --- a/cybertron/transport/rtps/sub_listener.cc +++ b/cyber/transport/rtps/sub_listener.cc @@ -14,13 +14,13 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/transport/rtps/sub_listener.h" +#include "cyber/transport/rtps/sub_listener.h" -#include "cybertron/common/log.h" -#include "cybertron/common/util.h" +#include "cyber/common/log.h" +#include "cyber/common/util.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { SubListener::SubListener(const NewMsgCallback& callback) @@ -73,5 +73,5 @@ void SubListener::onSubscriptionMatched( } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/transport/rtps/sub_listener.h b/cyber/transport/rtps/sub_listener.h similarity index 83% rename from cybertron/transport/rtps/sub_listener.h rename to cyber/transport/rtps/sub_listener.h index 669b53351a6..fc16abf62f8 100644 --- a/cybertron/transport/rtps/sub_listener.h +++ b/cyber/transport/rtps/sub_listener.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TRANSPORT_RTPS_SUB_LISTENER_H_ -#define CYBERTRON_TRANSPORT_RTPS_SUB_LISTENER_H_ +#ifndef CYBER_TRANSPORT_RTPS_SUB_LISTENER_H_ +#define CYBER_TRANSPORT_RTPS_SUB_LISTENER_H_ #include #include @@ -23,16 +23,16 @@ #include #include -#include "cybertron/transport/message/message_info.h" -#include "cybertron/transport/rtps/underlay_message.h" -#include "cybertron/transport/rtps/underlay_message_type.h" +#include "cyber/transport/message/message_info.h" +#include "cyber/transport/rtps/underlay_message.h" +#include "cyber/transport/rtps/underlay_message_type.h" #include "fastrtps/Domain.h" #include "fastrtps/subscriber/SampleInfo.h" #include "fastrtps/subscriber/Subscriber.h" #include "fastrtps/subscriber/SubscriberListener.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { class SubListener; @@ -58,7 +58,7 @@ class SubListener : public eprosima::fastrtps::SubscriberListener { }; } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TRANSPORT_RTPS_SUB_LISTENER_H_ +#endif // CYBER_TRANSPORT_RTPS_SUB_LISTENER_H_ diff --git a/cybertron/transport/rtps/underlay_message.cc b/cyber/transport/rtps/underlay_message.cc similarity index 97% rename from cybertron/transport/rtps/underlay_message.cc rename to cyber/transport/rtps/underlay_message.cc index 988dc3b632c..7470e00ee19 100644 --- a/cybertron/transport/rtps/underlay_message.cc +++ b/cyber/transport/rtps/underlay_message.cc @@ -30,10 +30,10 @@ char dummy; #include #include -#include "cybertron/transport/rtps/underlay_message.h" +#include "cyber/transport/rtps/underlay_message.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { UnderlayMessage::UnderlayMessage() { @@ -142,5 +142,5 @@ void UnderlayMessage::serializeKey(eprosima::fastcdr::Cdr &scdr) const { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/transport/rtps/underlay_message.h b/cyber/transport/rtps/underlay_message.h similarity index 73% rename from cybertron/transport/rtps/underlay_message.h rename to cyber/transport/rtps/underlay_message.h index 8cadec02d81..461e724209a 100644 --- a/cybertron/transport/rtps/underlay_message.h +++ b/cyber/transport/rtps/underlay_message.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TRANSPORT_RTPS_UNDERLAY_MESSAGE_H_ -#define CYBERTRON_TRANSPORT_RTPS_UNDERLAY_MESSAGE_H_ +#ifndef CYBER_TRANSPORT_RTPS_UNDERLAY_MESSAGE_H_ +#define CYBER_TRANSPORT_RTPS_UNDERLAY_MESSAGE_H_ #include #include @@ -25,12 +25,12 @@ #if defined(_WIN32) #if defined(EPROSIMA_USER_DLL_EXPORT) -#define ePcybertronima_user_DllExport __declspec(dllexport) +#define ePcyberima_user_DllExport __declspec(dllexport) #else -#define ePcybertronima_user_DllExport +#define ePcyberima_user_DllExport #endif #else -#define ePcybertronima_user_DllExport +#define ePcyberima_user_DllExport #endif #if defined(_WIN32) @@ -54,7 +54,7 @@ class Cdr; } // namespace eprosima namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { /*! @@ -67,43 +67,43 @@ class UnderlayMessage { /*! * @brief Default constructor. */ - ePcybertronima_user_DllExport UnderlayMessage(); + ePcyberima_user_DllExport UnderlayMessage(); /*! * @brief Default destructor. */ - ePcybertronima_user_DllExport ~UnderlayMessage(); + ePcyberima_user_DllExport ~UnderlayMessage(); /*! * @brief Copy constructor. * @param x Reference to the object UnderlayMessage that will be copied. */ - ePcybertronima_user_DllExport UnderlayMessage(const UnderlayMessage &x); + ePcyberima_user_DllExport UnderlayMessage(const UnderlayMessage &x); /*! * @brief Move constructor. * @param x Reference to the object UnderlayMessage that will be copied. */ - ePcybertronima_user_DllExport UnderlayMessage(UnderlayMessage &&x); + ePcyberima_user_DllExport UnderlayMessage(UnderlayMessage &&x); /*! * @brief Copy assignment. * @param x Reference to the object UnderlayMessage that will be copied. */ - ePcybertronima_user_DllExport UnderlayMessage &operator=( + ePcyberima_user_DllExport UnderlayMessage &operator=( const UnderlayMessage &x); /*! * @brief Move assignment. * @param x Reference to the object UnderlayMessage that will be copied. */ - ePcybertronima_user_DllExport UnderlayMessage &operator=(UnderlayMessage &&x); + ePcyberima_user_DllExport UnderlayMessage &operator=(UnderlayMessage &&x); /*! * @brief This function sets a value in member timestamp * @param _timestamp New value for member timestamp */ - inline ePcybertronima_user_DllExport void timestamp(int32_t _timestamp) { + inline ePcyberima_user_DllExport void timestamp(int32_t _timestamp) { m_timestamp = _timestamp; } @@ -111,7 +111,7 @@ class UnderlayMessage { * @brief This function returns the value of member timestamp * @return Value of member timestamp */ - inline ePcybertronima_user_DllExport int32_t timestamp() const { + inline ePcyberima_user_DllExport int32_t timestamp() const { return m_timestamp; } @@ -119,31 +119,31 @@ class UnderlayMessage { * @brief This function returns a reference to member timestamp * @return Reference to member timestamp */ - inline ePcybertronima_user_DllExport int32_t ×tamp() { + inline ePcyberima_user_DllExport int32_t ×tamp() { return m_timestamp; } /*! * @brief This function sets a value in member seq * @param _seq New value for member seq */ - inline ePcybertronima_user_DllExport void seq(int32_t _seq) { m_seq = _seq; } + inline ePcyberima_user_DllExport void seq(int32_t _seq) { m_seq = _seq; } /*! * @brief This function returns the value of member seq * @return Value of member seq */ - inline ePcybertronima_user_DllExport int32_t seq() const { return m_seq; } + inline ePcyberima_user_DllExport int32_t seq() const { return m_seq; } /*! * @brief This function returns a reference to member seq * @return Reference to member seq */ - inline ePcybertronima_user_DllExport int32_t &seq() { return m_seq; } + inline ePcyberima_user_DllExport int32_t &seq() { return m_seq; } /*! * @brief This function copies the value in member data * @param _data New value to be copied in member data */ - inline ePcybertronima_user_DllExport void data(const std::string &_data) { + inline ePcyberima_user_DllExport void data(const std::string &_data) { m_data = _data; } @@ -151,7 +151,7 @@ class UnderlayMessage { * @brief This function moves the value in member data * @param _data New value to be moved in member data */ - inline ePcybertronima_user_DllExport void data(std::string &&_data) { + inline ePcyberima_user_DllExport void data(std::string &&_data) { m_data = std::move(_data); } @@ -159,7 +159,7 @@ class UnderlayMessage { * @brief This function returns a constant reference to member data * @return Constant reference to member data */ - inline ePcybertronima_user_DllExport const std::string &data() const { + inline ePcyberima_user_DllExport const std::string &data() const { return m_data; } @@ -167,12 +167,12 @@ class UnderlayMessage { * @brief This function returns a reference to member data * @return Reference to member data */ - inline ePcybertronima_user_DllExport std::string &data() { return m_data; } + inline ePcyberima_user_DllExport std::string &data() { return m_data; } /*! * @brief This function copies the value in member datatype * @param _datatype New value to be copied in member datatype */ - inline ePcybertronima_user_DllExport void datatype( + inline ePcyberima_user_DllExport void datatype( const std::string &_datatype) { m_datatype = _datatype; } @@ -181,7 +181,7 @@ class UnderlayMessage { * @brief This function moves the value in member datatype * @param _datatype New value to be moved in member datatype */ - inline ePcybertronima_user_DllExport void datatype(std::string &&_datatype) { + inline ePcyberima_user_DllExport void datatype(std::string &&_datatype) { m_datatype = std::move(_datatype); } @@ -189,7 +189,7 @@ class UnderlayMessage { * @brief This function returns a constant reference to member datatype * @return Constant reference to member datatype */ - inline ePcybertronima_user_DllExport const std::string &datatype() const { + inline ePcyberima_user_DllExport const std::string &datatype() const { return m_datatype; } @@ -197,7 +197,7 @@ class UnderlayMessage { * @brief This function returns a reference to member datatype * @return Reference to member datatype */ - inline ePcybertronima_user_DllExport std::string &datatype() { + inline ePcyberima_user_DllExport std::string &datatype() { return m_datatype; } @@ -207,7 +207,7 @@ class UnderlayMessage { * @param current_alignment Buffer alignment. * @return Maximum serialized size. */ - ePcybertronima_user_DllExport static size_t getMaxCdrSerializedSize( + ePcyberima_user_DllExport static size_t getMaxCdrSerializedSize( size_t current_alignment = 0); /*! @@ -217,21 +217,21 @@ class UnderlayMessage { * @param current_alignment Buffer alignment. * @return Serialized size. */ - ePcybertronima_user_DllExport static size_t getCdrSerializedSize( + ePcyberima_user_DllExport static size_t getCdrSerializedSize( const UnderlayMessage &data, size_t current_alignment = 0); /*! * @brief This function serializes an object using CDR serialization. * @param cdr CDR serialization object. */ - ePcybertronima_user_DllExport void serialize( + ePcyberima_user_DllExport void serialize( eprosima::fastcdr::Cdr &cdr) const; // NOLINT /*! * @brief This function deserializes an object using CDR serialization. * @param cdr CDR serialization object. */ - ePcybertronima_user_DllExport void deserialize( + ePcyberima_user_DllExport void deserialize( eprosima::fastcdr::Cdr &cdr); // NOLINT /*! @@ -241,20 +241,20 @@ class UnderlayMessage { * @param current_alignment Buffer alignment. * @return Maximum serialized size. */ - ePcybertronima_user_DllExport static size_t getKeyMaxCdrSerializedSize( + ePcyberima_user_DllExport static size_t getKeyMaxCdrSerializedSize( size_t current_alignment = 0); /*! * @brief This function tells you if the Key has been defined for this type */ - ePcybertronima_user_DllExport static bool isKeyDefined(); + ePcyberima_user_DllExport static bool isKeyDefined(); /*! * @brief This function serializes the key members of an object using CDR * serialization. * @param cdr CDR serialization object. */ - ePcybertronima_user_DllExport void serializeKey( + ePcyberima_user_DllExport void serializeKey( eprosima::fastcdr::Cdr &cdr) const; // NOLINT private: @@ -265,7 +265,7 @@ class UnderlayMessage { }; } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TRANSPORT_RTPS_UNDERLAY_MESSAGE_H_ +#endif // CYBER_TRANSPORT_RTPS_UNDERLAY_MESSAGE_H_ diff --git a/cybertron/transport/rtps/underlay_message_type.cc b/cyber/transport/rtps/underlay_message_type.cc similarity index 97% rename from cybertron/transport/rtps/underlay_message_type.cc rename to cyber/transport/rtps/underlay_message_type.cc index 91f27faa320..18009bd7166 100644 --- a/cybertron/transport/rtps/underlay_message_type.cc +++ b/cyber/transport/rtps/underlay_message_type.cc @@ -22,10 +22,10 @@ #include #include -#include "cybertron/transport/rtps/underlay_message_type.h" +#include "cyber/transport/rtps/underlay_message_type.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { UnderlayMessageType::UnderlayMessageType() { @@ -126,5 +126,5 @@ bool UnderlayMessageType::getKey(void* data, InstanceHandle_t* handle) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/transport/rtps/underlay_message_type.h b/cyber/transport/rtps/underlay_message_type.h similarity index 84% rename from cybertron/transport/rtps/underlay_message_type.h rename to cyber/transport/rtps/underlay_message_type.h index acf72aa301b..4cb153f411a 100644 --- a/cybertron/transport/rtps/underlay_message_type.h +++ b/cyber/transport/rtps/underlay_message_type.h @@ -14,15 +14,15 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TRANSPORT_RTPS_UNDERLAY_MESSAGE_TYPE_H_ -#define CYBERTRON_TRANSPORT_RTPS_UNDERLAY_MESSAGE_TYPE_H_ +#ifndef CYBER_TRANSPORT_RTPS_UNDERLAY_MESSAGE_TYPE_H_ +#define CYBER_TRANSPORT_RTPS_UNDERLAY_MESSAGE_TYPE_H_ #include -#include "cybertron/transport/rtps/underlay_message.h" +#include "cyber/transport/rtps/underlay_message.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { /*! @@ -47,7 +47,7 @@ class UnderlayMessageType : public eprosima::fastrtps::TopicDataType { }; } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TRANSPORT_RTPS_UNDERLAY_MESSAGE_TYPE_H_ +#endif // CYBER_TRANSPORT_RTPS_UNDERLAY_MESSAGE_TYPE_H_ diff --git a/cybertron/transport/rtps_dispatcher_test.cc b/cyber/transport/rtps_dispatcher_test.cc similarity index 90% rename from cybertron/transport/rtps_dispatcher_test.cc rename to cyber/transport/rtps_dispatcher_test.cc index 0640e8209f8..cf94c587283 100644 --- a/cybertron/transport/rtps_dispatcher_test.cc +++ b/cyber/transport/rtps_dispatcher_test.cc @@ -17,15 +17,15 @@ #include #include -#include "cybertron/common/util.h" -#include "cybertron/proto/chatter.pb.h" -#include "cybertron/transport/common/identity.h" -#include "cybertron/transport/dispatcher/rtps_dispatcher.h" -#include "cybertron/transport/qos/qos_profile_conf.h" -#include "cybertron/transport/transport.h" +#include "cyber/common/util.h" +#include "cyber/proto/chatter.pb.h" +#include "cyber/transport/common/identity.h" +#include "cyber/transport/dispatcher/rtps_dispatcher.h" +#include "cyber/transport/qos/qos_profile_conf.h" +#include "cyber/transport/transport.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { TEST(RtpsDispatcherTest, constructor) { @@ -103,5 +103,5 @@ TEST(RtpsDispatcherTest, shutdown) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/transport/rtps_test.cc b/cyber/transport/rtps_test.cc similarity index 95% rename from cybertron/transport/rtps_test.cc rename to cyber/transport/rtps_test.cc index 02ef3d36659..e96d016b04a 100644 --- a/cybertron/transport/rtps_test.cc +++ b/cyber/transport/rtps_test.cc @@ -20,16 +20,16 @@ #include #include -#include "cybertron/common/global_data.h" -#include "cybertron/common/log.h" -#include "cybertron/transport/qos/qos_profile_conf.h" -#include "cybertron/transport/rtps/attributes_filler.h" -#include "cybertron/transport/rtps/participant.h" -#include "cybertron/transport/rtps/underlay_message.h" -#include "cybertron/transport/rtps/underlay_message_type.h" +#include "cyber/common/global_data.h" +#include "cyber/common/log.h" +#include "cyber/transport/qos/qos_profile_conf.h" +#include "cyber/transport/rtps/attributes_filler.h" +#include "cyber/transport/rtps/participant.h" +#include "cyber/transport/rtps/underlay_message.h" +#include "cyber/transport/rtps/underlay_message_type.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { TEST(AttributesFillerTest, fill_in_pub_attr_test) { @@ -207,5 +207,5 @@ TEST(UnderlayMessageTest, underlay_message_test) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/transport/rtps_transceiver_test.cc b/cyber/transport/rtps_transceiver_test.cc similarity index 93% rename from cybertron/transport/rtps_transceiver_test.cc rename to cyber/transport/rtps_transceiver_test.cc index cfd6ec2d6fd..d65039e6816 100644 --- a/cybertron/transport/rtps_transceiver_test.cc +++ b/cyber/transport/rtps_transceiver_test.cc @@ -20,14 +20,14 @@ #include #include -#include "cybertron/common/util.h" -#include "cybertron/proto/unit_test.pb.h" -#include "cybertron/transport/receiver/rtps_receiver.h" -#include "cybertron/transport/transmitter/rtps_transmitter.h" -#include "cybertron/transport/transport.h" +#include "cyber/common/util.h" +#include "cyber/proto/unit_test.pb.h" +#include "cyber/transport/receiver/rtps_receiver.h" +#include "cyber/transport/transmitter/rtps_transmitter.h" +#include "cyber/transport/transport.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { class RtpsTransceiverTest : public ::testing::Test { @@ -149,12 +149,12 @@ TEST_F(RtpsTransceiverTest, enable_and_disable) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { testing::InitGoogleTest(&argc, argv); auto res = RUN_ALL_TESTS(); - apollo::cybertron::transport::Transport::Shutdown(); + apollo::cyber::transport::Transport::Shutdown(); return res; } diff --git a/cybertron/transport/shm/block.cc b/cyber/transport/shm/block.cc similarity index 95% rename from cybertron/transport/shm/block.cc rename to cyber/transport/shm/block.cc index 9bce5262069..c49a681db0d 100644 --- a/cybertron/transport/shm/block.cc +++ b/cyber/transport/shm/block.cc @@ -14,12 +14,12 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/transport/shm/block.h" +#include "cyber/transport/shm/block.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { Block::Block() @@ -83,5 +83,5 @@ bool Block::Read(const uint8_t* src, std::string* msg, std::string* msg_info) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/transport/shm/block.h b/cyber/transport/shm/block.h similarity index 80% rename from cybertron/transport/shm/block.h rename to cyber/transport/shm/block.h index 660a7627860..eaed932b854 100644 --- a/cybertron/transport/shm/block.h +++ b/cyber/transport/shm/block.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TRANSPORT_SHM_BLOCK_H_ -#define CYBERTRON_TRANSPORT_SHM_BLOCK_H_ +#ifndef CYBER_TRANSPORT_SHM_BLOCK_H_ +#define CYBER_TRANSPORT_SHM_BLOCK_H_ #include #include @@ -23,15 +23,15 @@ #include #include -#include "cybertron/base/atomic_rw_lock.h" +#include "cyber/base/atomic_rw_lock.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { -using apollo::cybertron::base::AtomicRWLock; -using apollo::cybertron::base::ReadLockGuard; -using apollo::cybertron::base::WriteLockGuard; +using apollo::cyber::base::AtomicRWLock; +using apollo::cyber::base::ReadLockGuard; +using apollo::cyber::base::WriteLockGuard; class Block { public: @@ -56,7 +56,7 @@ class Block { }; } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TRANSPORT_SHM_BLOCK_H_ +#endif // CYBER_TRANSPORT_SHM_BLOCK_H_ diff --git a/cybertron/transport/shm/readable_info.cc b/cyber/transport/shm/readable_info.cc similarity index 94% rename from cybertron/transport/shm/readable_info.cc rename to cyber/transport/shm/readable_info.cc index 3ce1685a840..0f409c85c7c 100644 --- a/cybertron/transport/shm/readable_info.cc +++ b/cyber/transport/shm/readable_info.cc @@ -14,14 +14,14 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/transport/shm/readable_info.h" +#include "cyber/transport/shm/readable_info.h" #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { ReadableInfo::ReadableInfo() : host_id_(0), block_index_(0), channel_id_(0) {} @@ -61,5 +61,5 @@ bool ReadableInfo::DeserializeFrom(const std::string& src) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/transport/shm/readable_info.h b/cyber/transport/shm/readable_info.h similarity index 89% rename from cybertron/transport/shm/readable_info.h rename to cyber/transport/shm/readable_info.h index b201bbb1d1a..485f3dcfba5 100644 --- a/cybertron/transport/shm/readable_info.h +++ b/cyber/transport/shm/readable_info.h @@ -14,15 +14,15 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TRANSPORT_SHM_READABLE_INFO_H_ -#define CYBERTRON_TRANSPORT_SHM_READABLE_INFO_H_ +#ifndef CYBER_TRANSPORT_SHM_READABLE_INFO_H_ +#define CYBER_TRANSPORT_SHM_READABLE_INFO_H_ #include #include #include namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { class ReadableInfo; @@ -55,7 +55,7 @@ class ReadableInfo { }; } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TRANSPORT_SHM_READABLE_INFO_H_ +#endif // CYBER_TRANSPORT_SHM_READABLE_INFO_H_ diff --git a/cybertron/transport/shm/segment.cc b/cyber/transport/shm/segment.cc similarity index 97% rename from cybertron/transport/shm/segment.cc rename to cyber/transport/shm/segment.cc index 5881b2d3f21..bf2bc9e98a1 100644 --- a/cybertron/transport/shm/segment.cc +++ b/cyber/transport/shm/segment.cc @@ -14,16 +14,16 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/transport/shm/segment.h" +#include "cyber/transport/shm/segment.h" #include -#include "cybertron/common/log.h" -#include "cybertron/common/util.h" -#include "cybertron/transport/shm/shm_conf.h" +#include "cyber/common/log.h" +#include "cyber/common/util.h" +#include "cyber/transport/shm/shm_conf.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { Segment::Segment(uint64_t channel_id, const ReadWriteMode& mode) @@ -331,5 +331,5 @@ uint32_t Segment::GetNextWritableBlockIndex() { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/transport/shm/segment.h b/cyber/transport/shm/segment.h similarity index 85% rename from cybertron/transport/shm/segment.h rename to cyber/transport/shm/segment.h index 201024f4ecb..e0222f315e3 100644 --- a/cybertron/transport/shm/segment.h +++ b/cyber/transport/shm/segment.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TRANSPORT_SHM_SEGMENT_H_ -#define CYBERTRON_TRANSPORT_SHM_SEGMENT_H_ +#ifndef CYBER_TRANSPORT_SHM_SEGMENT_H_ +#define CYBER_TRANSPORT_SHM_SEGMENT_H_ #include #include @@ -26,12 +26,12 @@ #include #include -#include "cybertron/transport/shm/block.h" -#include "cybertron/transport/shm/shm_conf.h" -#include "cybertron/transport/shm/state.h" +#include "cyber/transport/shm/block.h" +#include "cyber/transport/shm/shm_conf.h" +#include "cyber/transport/shm/state.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { class Segment; @@ -75,7 +75,7 @@ class Segment { }; } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TRANSPORT_SHM_SEGMENT_H_ +#endif // CYBER_TRANSPORT_SHM_SEGMENT_H_ diff --git a/cybertron/transport/shm/shm_conf.cc b/cyber/transport/shm/shm_conf.cc similarity index 96% rename from cybertron/transport/shm/shm_conf.cc rename to cyber/transport/shm/shm_conf.cc index 04914d03581..9ed4cc8b511 100644 --- a/cybertron/transport/shm/shm_conf.cc +++ b/cyber/transport/shm/shm_conf.cc @@ -14,11 +14,11 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/transport/shm/shm_conf.h" -#include "cybertron/common/log.h" +#include "cyber/transport/shm/shm_conf.h" +#include "cyber/common/log.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { ShmConf::ShmConf() { Update(MESSAGE_SIZE_16K); } @@ -109,5 +109,5 @@ uint64_t ShmConf::GetBlockNum(const uint64_t& ceiling_msg_size) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/transport/shm/shm_conf.h b/cyber/transport/shm/shm_conf.h similarity index 93% rename from cybertron/transport/shm/shm_conf.h rename to cyber/transport/shm/shm_conf.h index 44a6ee241a2..b7c95c3dfbf 100644 --- a/cybertron/transport/shm/shm_conf.h +++ b/cyber/transport/shm/shm_conf.h @@ -14,14 +14,14 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TRANSPORT_SHM_SHM_CONF_H_ -#define CYBERTRON_TRANSPORT_SHM_SHM_CONF_H_ +#ifndef CYBER_TRANSPORT_SHM_SHM_CONF_H_ +#define CYBER_TRANSPORT_SHM_SHM_CONF_H_ #include #include namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { class ShmConf { @@ -76,7 +76,7 @@ class ShmConf { }; } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TRANSPORT_SHM_SHM_CONF_H_ +#endif // CYBER_TRANSPORT_SHM_SHM_CONF_H_ diff --git a/cybertron/transport/shm/state.cc b/cyber/transport/shm/state.cc similarity index 91% rename from cybertron/transport/shm/state.cc rename to cyber/transport/shm/state.cc index 0444d7c95d0..c614ed025a7 100644 --- a/cybertron/transport/shm/state.cc +++ b/cyber/transport/shm/state.cc @@ -14,10 +14,10 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/transport/shm/state.h" +#include "cyber/transport/shm/state.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { State::State(const uint64_t& ceiling_msg_size) @@ -26,5 +26,5 @@ State::State(const uint64_t& ceiling_msg_size) State::~State() {} } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/transport/shm/state.h b/cyber/transport/shm/state.h similarity index 91% rename from cybertron/transport/shm/state.h rename to cyber/transport/shm/state.h index 052d2a83f1c..64ff9ee780d 100644 --- a/cybertron/transport/shm/state.h +++ b/cyber/transport/shm/state.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TRANSPORT_SHM_STATE_H_ -#define CYBERTRON_TRANSPORT_SHM_STATE_H_ +#ifndef CYBER_TRANSPORT_SHM_STATE_H_ +#define CYBER_TRANSPORT_SHM_STATE_H_ #include #include @@ -23,7 +23,7 @@ #include namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { class State { @@ -65,7 +65,7 @@ class State { }; } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TRANSPORT_SHM_STATE_H_ +#endif // CYBER_TRANSPORT_SHM_STATE_H_ diff --git a/cybertron/transport/shm_dispatcher_test.cc b/cyber/transport/shm_dispatcher_test.cc similarity index 88% rename from cybertron/transport/shm_dispatcher_test.cc rename to cyber/transport/shm_dispatcher_test.cc index e7cf69e727a..0f5575e276a 100644 --- a/cybertron/transport/shm_dispatcher_test.cc +++ b/cyber/transport/shm_dispatcher_test.cc @@ -17,17 +17,17 @@ #include #include -#include "cybertron/common/global_data.h" -#include "cybertron/common/log.h" -#include "cybertron/common/util.h" -#include "cybertron/message/raw_message.h" -#include "cybertron/proto/chatter.pb.h" -#include "cybertron/transport/common/identity.h" -#include "cybertron/transport/dispatcher/shm_dispatcher.h" -#include "cybertron/transport/transport.h" +#include "cyber/common/global_data.h" +#include "cyber/common/log.h" +#include "cyber/common/util.h" +#include "cyber/message/raw_message.h" +#include "cyber/proto/chatter.pb.h" +#include "cyber/transport/common/identity.h" +#include "cyber/transport/dispatcher/shm_dispatcher.h" +#include "cyber/transport/transport.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { TEST(ShmDispatcherTest, constructor) { @@ -105,5 +105,5 @@ TEST(ShmDispatcherTest, shutdown) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/transport/shm_transceiver_test.cc b/cyber/transport/shm_transceiver_test.cc similarity index 94% rename from cybertron/transport/shm_transceiver_test.cc rename to cyber/transport/shm_transceiver_test.cc index 718ce1478c4..6c699a2f7eb 100644 --- a/cybertron/transport/shm_transceiver_test.cc +++ b/cyber/transport/shm_transceiver_test.cc @@ -20,14 +20,14 @@ #include #include -#include "cybertron/common/global_data.h" -#include "cybertron/common/util.h" -#include "cybertron/proto/unit_test.pb.h" -#include "cybertron/transport/receiver/shm_receiver.h" -#include "cybertron/transport/transmitter/shm_transmitter.h" +#include "cyber/common/global_data.h" +#include "cyber/common/util.h" +#include "cyber/proto/unit_test.pb.h" +#include "cyber/transport/receiver/shm_receiver.h" +#include "cyber/transport/transmitter/shm_transmitter.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { class ShmTransceiverTest : public ::testing::Test { @@ -148,5 +148,5 @@ TEST_F(ShmTransceiverTest, enable_and_disable) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/transport/transmitter/hybrid_transmitter.h b/cyber/transport/transmitter/hybrid_transmitter.h similarity index 90% rename from cybertron/transport/transmitter/hybrid_transmitter.h rename to cyber/transport/transmitter/hybrid_transmitter.h index 9569be6bb12..fc54d8f2d0c 100644 --- a/cybertron/transport/transmitter/hybrid_transmitter.h +++ b/cyber/transport/transmitter/hybrid_transmitter.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TRANSPORT_TRANSMITTER_HYBRID_TRANSMITTER_H_ -#define CYBERTRON_TRANSPORT_TRANSMITTER_HYBRID_TRANSMITTER_H_ +#ifndef CYBER_TRANSPORT_TRANSMITTER_HYBRID_TRANSMITTER_H_ +#define CYBER_TRANSPORT_TRANSMITTER_HYBRID_TRANSMITTER_H_ #include #include @@ -26,25 +26,25 @@ #include #include -#include "cybertron/common/global_data.h" -#include "cybertron/common/log.h" -#include "cybertron/common/types.h" -#include "cybertron/proto/role_attributes.pb.h" -#include "cybertron/proto/transport_conf.pb.h" -#include "cybertron/transport/message/history.h" -#include "cybertron/transport/rtps/participant.h" -#include "cybertron/transport/transmitter/intra_transmitter.h" -#include "cybertron/transport/transmitter/rtps_transmitter.h" -#include "cybertron/transport/transmitter/shm_transmitter.h" -#include "cybertron/transport/transmitter/transmitter.h" +#include "cyber/common/global_data.h" +#include "cyber/common/log.h" +#include "cyber/common/types.h" +#include "cyber/proto/role_attributes.pb.h" +#include "cyber/proto/transport_conf.pb.h" +#include "cyber/transport/message/history.h" +#include "cyber/transport/rtps/participant.h" +#include "cyber/transport/transmitter/intra_transmitter.h" +#include "cyber/transport/transmitter/rtps_transmitter.h" +#include "cyber/transport/transmitter/shm_transmitter.h" +#include "cyber/transport/transmitter/transmitter.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { -using apollo::cybertron::proto::OptionalMode; -using apollo::cybertron::proto::QosDurabilityPolicy; -using apollo::cybertron::proto::RoleAttributes; +using apollo::cyber::proto::OptionalMode; +using apollo::cyber::proto::QosDurabilityPolicy; +using apollo::cyber::proto::RoleAttributes; template class HybridTransmitter : public Transmitter { @@ -302,7 +302,7 @@ Relation HybridTransmitter::GetRelation( } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TRANSPORT_TRANSMITTER_HYBRID_TRANSMITTER_H_ +#endif // CYBER_TRANSPORT_TRANSMITTER_HYBRID_TRANSMITTER_H_ diff --git a/cybertron/transport/transmitter/intra_transmitter.h b/cyber/transport/transmitter/intra_transmitter.h similarity index 85% rename from cybertron/transport/transmitter/intra_transmitter.h rename to cyber/transport/transmitter/intra_transmitter.h index 26c5153bfb1..35ae6f6e89b 100644 --- a/cybertron/transport/transmitter/intra_transmitter.h +++ b/cyber/transport/transmitter/intra_transmitter.h @@ -14,18 +14,18 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TRANSPORT_TRANSMITTER_INTRA_TRANSMITTER_H_ -#define CYBERTRON_TRANSPORT_TRANSMITTER_INTRA_TRANSMITTER_H_ +#ifndef CYBER_TRANSPORT_TRANSMITTER_INTRA_TRANSMITTER_H_ +#define CYBER_TRANSPORT_TRANSMITTER_INTRA_TRANSMITTER_H_ #include #include -#include "cybertron/common/log.h" -#include "cybertron/transport/dispatcher/intra_dispatcher.h" -#include "cybertron/transport/transmitter/transmitter.h" +#include "cyber/common/log.h" +#include "cyber/transport/dispatcher/intra_dispatcher.h" +#include "cyber/transport/transmitter/transmitter.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { template @@ -85,7 +85,7 @@ bool IntraTransmitter::Transmit(const MessagePtr& msg, } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TRANSPORT_TRANSMITTER_INTRA_TRANSMITTER_H_ +#endif // CYBER_TRANSPORT_TRANSMITTER_INTRA_TRANSMITTER_H_ diff --git a/cybertron/transport/transmitter/rtps_transmitter.h b/cyber/transport/transmitter/rtps_transmitter.h similarity index 88% rename from cybertron/transport/transmitter/rtps_transmitter.h rename to cyber/transport/transmitter/rtps_transmitter.h index e819f0d298f..54864c2aac2 100644 --- a/cybertron/transport/transmitter/rtps_transmitter.h +++ b/cyber/transport/transmitter/rtps_transmitter.h @@ -14,24 +14,24 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TRANSPORT_TRANSMITTER_RTPS_TRANSMITTER_H_ -#define CYBERTRON_TRANSPORT_TRANSMITTER_RTPS_TRANSMITTER_H_ +#ifndef CYBER_TRANSPORT_TRANSMITTER_RTPS_TRANSMITTER_H_ +#define CYBER_TRANSPORT_TRANSMITTER_RTPS_TRANSMITTER_H_ #include #include -#include "cybertron/common/log.h" -#include "cybertron/message/message_traits.h" -#include "cybertron/transport/rtps/attributes_filler.h" -#include "cybertron/transport/rtps/participant.h" -#include "cybertron/transport/transmitter/transmitter.h" +#include "cyber/common/log.h" +#include "cyber/message/message_traits.h" +#include "cyber/transport/rtps/attributes_filler.h" +#include "cyber/transport/rtps/participant.h" +#include "cyber/transport/transmitter/transmitter.h" #include "fastrtps/Domain.h" #include "fastrtps/attributes/PublisherAttributes.h" #include "fastrtps/participant/Participant.h" #include "fastrtps/publisher/Publisher.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { template @@ -126,7 +126,7 @@ bool RtpsTransmitter::Transmit(const M& msg, const MessageInfo& msg_info) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TRANSPORT_TRANSMITTER_RTPS_TRANSMITTER_H_ +#endif // CYBER_TRANSPORT_TRANSMITTER_RTPS_TRANSMITTER_H_ diff --git a/cybertron/transport/transmitter/shm_transmitter.h b/cyber/transport/transmitter/shm_transmitter.h similarity index 86% rename from cybertron/transport/transmitter/shm_transmitter.h rename to cyber/transport/transmitter/shm_transmitter.h index 2aa1e4c2285..ccdcc18ca8b 100644 --- a/cybertron/transport/transmitter/shm_transmitter.h +++ b/cyber/transport/transmitter/shm_transmitter.h @@ -14,8 +14,8 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TRANSPORT_TRANSMITTER_SHM_TRANSMITTER_H_ -#define CYBERTRON_TRANSPORT_TRANSMITTER_SHM_TRANSMITTER_H_ +#ifndef CYBER_TRANSPORT_TRANSMITTER_SHM_TRANSMITTER_H_ +#define CYBER_TRANSPORT_TRANSMITTER_SHM_TRANSMITTER_H_ #include #include @@ -28,18 +28,18 @@ #include #include -#include "cybertron/common/global_data.h" -#include "cybertron/common/log.h" -#include "cybertron/common/util.h" -#include "cybertron/message/message_traits.h" -#include "cybertron/proto/transport_conf.pb.h" -#include "cybertron/transport/common/syscall_wrapper.h" -#include "cybertron/transport/shm/readable_info.h" -#include "cybertron/transport/shm/segment.h" -#include "cybertron/transport/transmitter/transmitter.h" +#include "cyber/common/global_data.h" +#include "cyber/common/log.h" +#include "cyber/common/util.h" +#include "cyber/message/message_traits.h" +#include "cyber/proto/transport_conf.pb.h" +#include "cyber/transport/common/syscall_wrapper.h" +#include "cyber/transport/shm/readable_info.h" +#include "cyber/transport/shm/segment.h" +#include "cyber/transport/transmitter/transmitter.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { template @@ -148,7 +148,7 @@ bool ShmTransmitter::Transmit(const M& msg, const MessageInfo& msg_info) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TRANSPORT_TRANSMITTER_SHM_TRANSMITTER_H_ +#endif // CYBER_TRANSPORT_TRANSMITTER_SHM_TRANSMITTER_H_ diff --git a/cybertron/transport/transmitter/transmitter.h b/cyber/transport/transmitter/transmitter.h similarity index 83% rename from cybertron/transport/transmitter/transmitter.h rename to cyber/transport/transmitter/transmitter.h index e6f3e82beee..508c2d0e04f 100644 --- a/cybertron/transport/transmitter/transmitter.h +++ b/cyber/transport/transmitter/transmitter.h @@ -14,23 +14,23 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TRANSPORT_TRANSMITTER_TRANSMITTER_H_ -#define CYBERTRON_TRANSPORT_TRANSMITTER_TRANSMITTER_H_ +#ifndef CYBER_TRANSPORT_TRANSMITTER_TRANSMITTER_H_ +#define CYBER_TRANSPORT_TRANSMITTER_TRANSMITTER_H_ #include #include #include -#include "cybertron/event/perf_event_cache.h" -#include "cybertron/transport/common/endpoint.h" -#include "cybertron/transport/message/message_info.h" +#include "cyber/event/perf_event_cache.h" +#include "cyber/transport/common/endpoint.h" +#include "cyber/transport/message/message_info.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { -using apollo::cybertron::event::PerfEventCache; -using apollo::cybertron::event::TransPerf; +using apollo::cyber::event::PerfEventCache; +using apollo::cyber::event::TransPerf; template class Transmitter : public Endpoint { @@ -89,7 +89,7 @@ void Transmitter::Disable(const RoleAttributes& opposite_attr) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TRANSPORT_TRANSMITTER_TRANSMITTER_H_ +#endif // CYBER_TRANSPORT_TRANSMITTER_TRANSMITTER_H_ diff --git a/cybertron/transport/transport.cc b/cyber/transport/transport.cc similarity index 93% rename from cybertron/transport/transport.cc rename to cyber/transport/transport.cc index e33d598f9e4..862f5e72b80 100644 --- a/cybertron/transport/transport.cc +++ b/cyber/transport/transport.cc @@ -14,15 +14,15 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/transport/transport.h" +#include "cyber/transport/transport.h" #include #include -#include "cybertron/common/global_data.h" +#include "cyber/common/global_data.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { static std::atomic shutdown_ = {false}; @@ -63,5 +63,5 @@ ParticipantPtr Transport::participant() { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo diff --git a/cybertron/transport/transport.h b/cyber/transport/transport.h similarity index 80% rename from cybertron/transport/transport.h rename to cyber/transport/transport.h index 117340aeb38..479437e2d85 100644 --- a/cybertron/transport/transport.h +++ b/cyber/transport/transport.h @@ -14,31 +14,31 @@ * limitations under the License. *****************************************************************************/ -#ifndef CYBERTRON_TRANSPORT_TRANSPORT_H_ -#define CYBERTRON_TRANSPORT_TRANSPORT_H_ +#ifndef CYBER_TRANSPORT_TRANSPORT_H_ +#define CYBER_TRANSPORT_TRANSPORT_H_ #include #include -#include "cybertron/proto/transport_conf.pb.h" -#include "cybertron/transport/qos/qos_profile_conf.h" -#include "cybertron/transport/receiver/hybrid_receiver.h" -#include "cybertron/transport/receiver/intra_receiver.h" -#include "cybertron/transport/receiver/receiver.h" -#include "cybertron/transport/receiver/rtps_receiver.h" -#include "cybertron/transport/receiver/shm_receiver.h" -#include "cybertron/transport/rtps/participant.h" -#include "cybertron/transport/transmitter/hybrid_transmitter.h" -#include "cybertron/transport/transmitter/intra_transmitter.h" -#include "cybertron/transport/transmitter/rtps_transmitter.h" -#include "cybertron/transport/transmitter/shm_transmitter.h" -#include "cybertron/transport/transmitter/transmitter.h" +#include "cyber/proto/transport_conf.pb.h" +#include "cyber/transport/qos/qos_profile_conf.h" +#include "cyber/transport/receiver/hybrid_receiver.h" +#include "cyber/transport/receiver/intra_receiver.h" +#include "cyber/transport/receiver/receiver.h" +#include "cyber/transport/receiver/rtps_receiver.h" +#include "cyber/transport/receiver/shm_receiver.h" +#include "cyber/transport/rtps/participant.h" +#include "cyber/transport/transmitter/hybrid_transmitter.h" +#include "cyber/transport/transmitter/intra_transmitter.h" +#include "cyber/transport/transmitter/rtps_transmitter.h" +#include "cyber/transport/transmitter/shm_transmitter.h" +#include "cyber/transport/transmitter/transmitter.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { -using apollo::cybertron::proto::OptionalMode; +using apollo::cyber::proto::OptionalMode; class Transport { public: @@ -143,7 +143,7 @@ auto Transport::CreateReceiver( } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo -#endif // CYBERTRON_TRANSPORT_TRANSPORT_H_ +#endif // CYBER_TRANSPORT_TRANSPORT_H_ diff --git a/cybertron/transport/transport_test.cc b/cyber/transport/transport_test.cc similarity index 91% rename from cybertron/transport/transport_test.cc rename to cyber/transport/transport_test.cc index f9fc90cdb34..15e8b190abe 100644 --- a/cybertron/transport/transport_test.cc +++ b/cyber/transport/transport_test.cc @@ -18,12 +18,12 @@ #include #include -#include "cybertron/proto/unit_test.pb.h" -#include "cybertron/transport/common/identity.h" -#include "cybertron/transport/transport.h" +#include "cyber/proto/unit_test.pb.h" +#include "cyber/transport/common/identity.h" +#include "cyber/transport/transport.h" namespace apollo { -namespace cybertron { +namespace cyber { namespace transport { using TransmitterPtr = std::shared_ptr>; @@ -72,12 +72,12 @@ TEST(TransportTest, create_receiver) { } } // namespace transport -} // namespace cybertron +} // namespace cyber } // namespace apollo int main(int argc, char** argv) { testing::InitGoogleTest(&argc, argv); auto res = RUN_ALL_TESTS(); - apollo::cybertron::transport::Transport::Shutdown(); + apollo::cyber::transport::Transport::Shutdown(); return res; } diff --git a/cybertron/BUILD b/cybertron/BUILD deleted file mode 100644 index c2abaed4914..00000000000 --- a/cybertron/BUILD +++ /dev/null @@ -1,126 +0,0 @@ -load("//tools:cpplint.bzl", "cpplint") - -package(default_visibility = ["//visibility:public"]) - -cc_library( - name = "cybertron", - deps = [ - "//cybertron:cybertron_core", - ], - linkstatic = False, -) - -cc_binary( - name = "mainboard", - srcs = glob([ - "mainboard/*.cc", - "mainboard/*.h", - ]), - deps = [ - ":cybertron_core", - "//cybertron/proto:dag_config_cc_proto", - ], - copts = [ - "-pthread", - ], - linkstatic = False, -) - -cc_binary( - name = "libcybertron.so", - deps = [ - ":cybertron_core", - "@fastrtps//:fastrtps", - ], - #TODO: Using deps instead. - linkopts = [ - "-luuid", - ], - linkshared = True, - linkstatic = True, -) - -cc_library( - name = "binary", - hdrs = [ - "binary.h", - ], -) - -cc_library( - name = "state", - srcs = [ - "state.cc", - ], - hdrs = [ - "state.h", - ], -) - -cc_library( - name = "init", - hdrs = [ - "cybertron.h", - "init.h", - ], - deps = [ - "state", - ], -) - -cc_library( - name = "cybertron_core", - srcs = [ - "cybertron.cc", - "init.cc", - ], - deps = [ - "//cybertron:binary", - "//cybertron:state", - "//cybertron/base", - "//cybertron/blocker:blocker_manager", - "//cybertron/common", - "//cybertron/component:component", - "//cybertron/component:timer_component", - "//cybertron/class_loader:class_loader", - "//cybertron/class_loader:class_loader_manager", - "//cybertron/croutine:croutine", - "//cybertron/data:data", - "//cybertron/event:perf_event", - "//cybertron/event:perf_event_cache", - "//cybertron:init", - "//cybertron/logger:logger", - "//cybertron/logger:async_logger", - "//cybertron/message:message_traits", - "//cybertron/message:raw_message_traits", - "//cybertron/message:py_message_traits", - "//cybertron/message:protobuf_traits", - "//cybertron/message:intra_message_traits", - "//cybertron/node:node", - "//cybertron/proto:run_mode_conf_cc_proto", - "//cybertron/parameter:parameter_client", - "//cybertron/parameter:parameter_server", - "//cybertron/record:record", - "//cybertron/scheduler:scheduler", - "//cybertron/service:client", - "//cybertron/service:service", - "//cybertron/service_discovery:topology_manager", - "//cybertron/task:task", - "//cybertron/time:time", - "//cybertron/time:duration", - "//cybertron/time:rate", - "//cybertron/timer:timer", - "//cybertron/transport:transport_lib", - "//third_party/tf2:tf2", - "@fastrtps", - ], - linkopts = [ - "-luuid", - "-lprotobuf", - "-lglog", - "-lgflags", - ], -) - - -cpplint() diff --git a/cybertron/README.md b/cybertron/README.md deleted file mode 100644 index a2b7d2d0966..00000000000 --- a/cybertron/README.md +++ /dev/null @@ -1,2 +0,0 @@ -# Introduction - Cybertron is a collection of software frameworks for self-driving application development, providing operating system-like functionality on a heterogeneous computer. This allows you to build, test, and deploy self-driving applications more efficient. diff --git a/cybertron/message/message_traits.h b/cybertron/message/message_traits.h deleted file mode 100644 index 79cf1678dd9..00000000000 --- a/cybertron/message/message_traits.h +++ /dev/null @@ -1,25 +0,0 @@ -/****************************************************************************** - * Copyright 2018 The Apollo Authors. All Rights Reserved. - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - *****************************************************************************/ - -#ifndef CYBERTRON_MESSAGE_MESSAGE_TRAITS_H_ -#define CYBERTRON_MESSAGE_MESSAGE_TRAITS_H_ - -#include "cybertron/message/intra_message_traits.h" -#include "cybertron/message/protobuf_traits.h" -#include "cybertron/message/py_message_traits.h" -#include "cybertron/message/raw_message_traits.h" - -#endif // CYBERTRON_MESSAGE_MESSAGE_TRAITS_H_ diff --git a/cybertron/node/BUILD b/cybertron/node/BUILD deleted file mode 100644 index f961a883604..00000000000 --- a/cybertron/node/BUILD +++ /dev/null @@ -1,65 +0,0 @@ -load("//tools:cpplint.bzl", "cpplint") - -package(default_visibility = ["//visibility:public"]) - -cc_library( - name = "reader_base", - hdrs = glob([ - "reader_base.h", - ]), - deps = [ - "//cybertron/transport:transport_lib", - "//cybertron/common:common", - "//cybertron/event:perf_event_cache", - ], -) - -cc_library( - name = "node", - srcs = glob([ - "node.cc", - ]), - hdrs = glob([ - "*.h", - ]), - deps = [ - "//cybertron/transport:transport_lib", - "//cybertron/blocker:intra_reader", - "//cybertron/blocker:intra_writer", - "//cybertron/croutine:croutine", - "//cybertron/data:data_visitor", - "//cybertron/scheduler:scheduler", - "//cybertron/service:client", - "//cybertron/service:service", - "//cybertron/service_discovery:topology_manager", - "//cybertron/proto:topology_change_cc_proto", - ], -) - -cc_test( - name = "node_test", - size = "small", - srcs = [ - "node_test.cc", - ], - deps = [ - "//cybertron", - "//cybertron/proto:unit_test_cc_proto", - "@gtest//:main", - ], -) - -cc_test( - name = "writer_reader_test", - size = "small", - srcs = [ - "writer_reader_test.cc", - ], - deps = [ - "//cybertron", - "//cybertron/proto:unit_test_cc_proto", - "@gtest//:main", - ], -) - -cpplint() diff --git a/cybertron/proto/cyber_config.proto b/cybertron/proto/cyber_config.proto deleted file mode 100644 index 67944d9b96c..00000000000 --- a/cybertron/proto/cyber_config.proto +++ /dev/null @@ -1,21 +0,0 @@ -syntax = "proto2"; - -package apollo.cybertron.proto; - -import "cybertron/proto/routine_conf.proto"; -import "cybertron/proto/scheduler_conf.proto"; -import "cybertron/proto/transport_conf.proto"; -import "cybertron/proto/log_conf.proto"; -import "cybertron/proto/perf_conf.proto"; -import "cybertron/proto/run_mode_conf.proto"; -import "cybertron/proto/record_conf.proto"; - -message CyberConfig { - optional LogConf log_conf = 1; - optional RoutineConf routine_conf = 2; - optional SchedulerConf scheduler_conf = 3; - optional TransportConf transport_conf = 4; - optional PerfConf perf_conf = 5; - optional RunModeConf run_mode_conf = 6; - optional RecordConf record_conf = 7; -} diff --git a/cybertron/setup.bash b/cybertron/setup.bash deleted file mode 100755 index 249112dc888..00000000000 --- a/cybertron/setup.bash +++ /dev/null @@ -1,16 +0,0 @@ -export CYBERTRON_PATH=$(cd "$(dirname "${BASH_SOURCE[0]}")" && pwd) -binary_path="/apollo/bazel-bin/cybertron" -tool_path="/apollo/bazel-bin/cybertron/tools" -PYTHON_LD_PATH="/apollo/bazel-bin/cybertron/py_wrapper" -launch_path="${CYBERTRON_PATH}/tools/cyber_launch" -qt_path=${CYBERTRON_PATH}/../third_party/Qt5.5.1/5.5/gcc_64 - -export LD_LIBRARY_PATH=${qt_path}/lib:$LD_LIBRARY_PATH -export QT_QPA_PLATFORM_PLUGIN_PATH=${qt_path}/plugins -export PATH=${binary_path}:${tool_path}:${launch_path}:${qt_path}/bin:$PATH -export PYTHONPATH=${PYTHON_LD_PATH}:${CYBERTRON_PATH}/python:$PYTHONPATH - -export CYBER_DOMAIN_ID=80 -export CYBER_IP=127.0.0.1 - -source ${CYBERTRON_PATH}/tools/cyber_tools_auto_complete.bash diff --git a/cybertron/tools/setup.bash b/cybertron/tools/setup.bash deleted file mode 100755 index 6d39cb573be..00000000000 --- a/cybertron/tools/setup.bash +++ /dev/null @@ -1,14 +0,0 @@ -export CYBERTRON_PATH=$(cd "$(dirname "${BASH_SOURCE[0]}")" && pwd) -library_path="${CYBERTRON_PATH}/lib:${CYBERTRON_PATH}/third_party:${CYBERTRON_PATH}/lib/python" -binary_path=${CYBERTRON_PATH}/bin/ -qt_path=${CYBERTRON_PATH}/../third_party/Qt5.5.1/5.5/gcc_64 - -export LD_LIBRARY_PATH=${library_path}:${qt_path}/lib:$LD_LIBRARY_PATH -export QT_QPA_PLATFORM_PLUGIN_PATH=${CYBERTRON_PATH}/third_party/plugins -export PATH=${binary_path}:${qt_path}/bin:$PATH -export PYTHONPATH=${CYBERTRON_PATH}/lib/python:${CYBERTRON_PATH}/lib/python/cybertron:${CYBERTRON_PATH}/lib/python/cybertron/proto:$PYTHONPATH - -export CYBER_DOMAIN_ID=80 -export CYBER_IP=127.0.0.1 - -source ${CYBERTRON_PATH}/cyber_tools_auto_complete.bash diff --git a/cybertron/transport/rtps/BUILD b/cybertron/transport/rtps/BUILD deleted file mode 100644 index d95dbc6d4fa..00000000000 --- a/cybertron/transport/rtps/BUILD +++ /dev/null @@ -1,26 +0,0 @@ -load("//tools:cpplint.bzl", "cpplint") - -package(default_visibility = ["//visibility:public"]) - -cc_library( - name = "rtps_lib", - srcs = glob([ - "*.cc", - ]), - hdrs = glob([ - "*.h", - ]), - deps = [ - "//cybertron/common", - "//cybertron/base:atomic_hash_map", - "//cybertron/base:atomic_rw_lock", - "//cybertron/proto:qos_profile_cc_proto", - "//cybertron/proto:transport_conf_cc_proto", - "//cybertron/transport/common:transport_common", - "//cybertron/transport/message:transport_message_lib", - "//cybertron/transport/qos:qos_lib", - "@fastrtps//:fastrtps", - ], -) - -cpplint() diff --git a/modules/calibration/lidar_ex_checker/BUILD b/modules/calibration/lidar_ex_checker/BUILD index 005c9b1ba6d..599c0de72a0 100644 --- a/modules/calibration/lidar_ex_checker/BUILD +++ b/modules/calibration/lidar_ex_checker/BUILD @@ -12,7 +12,7 @@ package(default_visibility = ["//visibility:public"]) # deps = [ # "//modules/calibration/lidar_ex_checker/common:lidar_ex_checker_common", # "//modules/common:apollo_app", -# "//cybertron", +# "//cyber", # "//modules/localization/proto:gps_proto", # "//modules/perception/common:pcl_util", # "@vtk", @@ -28,7 +28,7 @@ package(default_visibility = ["//visibility:public"]) # deps = [ # ":lidar_ex_checker_lib", # "//external:gflags", -# "//cybertron", +# "//cyber", # "@pcl", # "@ros//:ros_common", # ], diff --git a/modules/calibration/lidar_ex_checker/lidar_ex_checker.cc b/modules/calibration/lidar_ex_checker/lidar_ex_checker.cc index 74c0ca83c0a..e0ce97a5608 100644 --- a/modules/calibration/lidar_ex_checker/lidar_ex_checker.cc +++ b/modules/calibration/lidar_ex_checker/lidar_ex_checker.cc @@ -24,7 +24,7 @@ #include "modules/calibration/lidar_ex_checker/common/lidar_ex_checker_gflags.h" #include "modules/common/adapters/adapter_manager.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace calibration { diff --git a/modules/calibration/lidar_ex_checker/main.cc b/modules/calibration/lidar_ex_checker/main.cc index 80a93b60b32..a737f642a3c 100644 --- a/modules/calibration/lidar_ex_checker/main.cc +++ b/modules/calibration/lidar_ex_checker/main.cc @@ -15,7 +15,7 @@ *****************************************************************************/ #include "gflags/gflags.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "ros/include/ros/ros.h" #include "modules/calibration/lidar_ex_checker/lidar_ex_checker.h" diff --git a/modules/calibration/modes/mkz_rtk/record_replay.launch b/modules/calibration/modes/mkz_rtk/record_replay.launch index 1c410bcbbd4..7c9c70decda 100644 --- a/modules/calibration/modes/mkz_rtk/record_replay.launch +++ b/modules/calibration/modes/mkz_rtk/record_replay.launch @@ -1,7 +1,7 @@ - - cybertron modules list config + + cyber modules list config 1.0.0 @@ -46,4 +46,4 @@ 1.0.0 - + diff --git a/modules/calibration/modes/mkz_standard/close_loop.launch b/modules/calibration/modes/mkz_standard/close_loop.launch index 4fc6e56affd..3be6127b2be 100644 --- a/modules/calibration/modes/mkz_standard/close_loop.launch +++ b/modules/calibration/modes/mkz_standard/close_loop.launch @@ -1,7 +1,7 @@ - - cybertron modules list config + + cyber modules list config 1.0.0 @@ -95,4 +95,4 @@ 1.0.0 - + diff --git a/modules/calibration/modes/udev_standard/calibrantion.launch b/modules/calibration/modes/udev_standard/calibrantion.launch index 03ee115de24..89e826e8756 100644 --- a/modules/calibration/modes/udev_standard/calibrantion.launch +++ b/modules/calibration/modes/udev_standard/calibrantion.launch @@ -1,7 +1,7 @@ - - cybertron modules list config + + cyber modules list config 1.0.0 @@ -102,4 +102,4 @@ 1.0.0 - + diff --git a/modules/calibration/modes/udev_standard/close_loop.launch b/modules/calibration/modes/udev_standard/close_loop.launch index 864d1bbc1ad..c795f9bb526 100644 --- a/modules/calibration/modes/udev_standard/close_loop.launch +++ b/modules/calibration/modes/udev_standard/close_loop.launch @@ -1,7 +1,7 @@ - - cybertron modules list config + + cyber modules list config 1.0.0 @@ -95,4 +95,4 @@ 1.0.0 - + diff --git a/modules/calibration/republish_msg/BUILD b/modules/calibration/republish_msg/BUILD index 33e03a8a256..14d2cf5dd82 100644 --- a/modules/calibration/republish_msg/BUILD +++ b/modules/calibration/republish_msg/BUILD @@ -10,7 +10,7 @@ package(default_visibility = ["//visibility:public"]) # "//modules/calibration/republish_msg/common:republish_msg_common", # "//modules/calibration/republish_msg/proto:relative_odometry_proto", # "//modules/common:apollo_app", -# "//cybertron", +# "//cyber", # "//modules/drivers/gnss/proto:ins_proto", # "//modules/localization/proto:gps_proto", # ], @@ -26,7 +26,7 @@ package(default_visibility = ["//visibility:public"]) # deps = [ # ":republish_msg_lib", # "//external:gflags", -# "//cybertron", +# "//cyber", # "@ros//:ros_common", # ], # ) diff --git a/modules/calibration/republish_msg/main.cc b/modules/calibration/republish_msg/main.cc index 1e7034c6d96..c15b8c6ed47 100644 --- a/modules/calibration/republish_msg/main.cc +++ b/modules/calibration/republish_msg/main.cc @@ -15,7 +15,7 @@ *****************************************************************************/ #include "gflags/gflags.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "ros/include/ros/ros.h" #include "modules/calibration/republish_msg/republish_msg.h" diff --git a/modules/calibration/republish_msg/republish_msg.cc b/modules/calibration/republish_msg/republish_msg.cc index 83e4f56dde5..04672d78695 100644 --- a/modules/calibration/republish_msg/republish_msg.cc +++ b/modules/calibration/republish_msg/republish_msg.cc @@ -17,7 +17,7 @@ #include "modules/calibration/republish_msg/common/republish_msg_gflags.h" #include "modules/calibration/republish_msg/republish_msg.h" #include "modules/common/adapters/adapter_manager.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "ros/include/ros/ros.h" namespace apollo { diff --git a/modules/canbus/BUILD b/modules/canbus/BUILD index 6e0d3de198d..b64be95df06 100644 --- a/modules/canbus/BUILD +++ b/modules/canbus/BUILD @@ -9,7 +9,7 @@ cc_library( copts = ["-DMODULE_NAME=\\\"canbus\\\""], deps = [ "//external:gflags", - "//cybertron", + "//cyber", "//modules/canbus/common:canbus_common", "//modules/canbus/vehicle:vehicle_factory", "//modules/common", diff --git a/modules/canbus/canbus_component.cc b/modules/canbus/canbus_component.cc index 3f7c8f1d476..2c186324a46 100644 --- a/modules/canbus/canbus_component.cc +++ b/modules/canbus/canbus_component.cc @@ -104,12 +104,12 @@ bool CanbusComponent::Init() { << " initialized with canbus conf as : " << canbus_conf_.vehicle_parameter().ShortDebugString(); - cybertron::ReaderConfig guardian_cmd_reader_config; + cyber::ReaderConfig guardian_cmd_reader_config; guardian_cmd_reader_config.channel_name = FLAGS_guardian_topic; guardian_cmd_reader_config.pending_queue_size = FLAGS_guardian_cmd_pending_queue_size; - cybertron::ReaderConfig control_cmd_reader_config; + cyber::ReaderConfig control_cmd_reader_config; control_cmd_reader_config.channel_name = FLAGS_control_command_topic; control_cmd_reader_config.pending_queue_size = FLAGS_control_cmd_pending_queue_size; diff --git a/modules/canbus/canbus_component.h b/modules/canbus/canbus_component.h index 267f0bdb934..b3243d46802 100644 --- a/modules/canbus/canbus_component.h +++ b/modules/canbus/canbus_component.h @@ -25,10 +25,10 @@ #include #include -#include "cybertron/common/macros.h" -#include "cybertron/component/timer_component.h" -#include "cybertron/cybertron.h" -#include "cybertron/timer/timer.h" +#include "cyber/common/macros.h" +#include "cyber/component/timer_component.h" +#include "cyber/cyber.h" +#include "cyber/timer/timer.h" #include "modules/canbus/proto/chassis_detail.pb.h" #include "modules/drivers/canbus/proto/can_card_parameter.pb.h" @@ -50,8 +50,8 @@ namespace apollo { namespace canbus { -using apollo::cybertron::Reader; -using apollo::cybertron::Writer; +using apollo::cyber::Reader; +using apollo::cyber::Writer; /** * @class Canbus @@ -59,7 +59,7 @@ using apollo::cybertron::Writer; * @brief canbus module main class. * It processes the control data to send protocol messages to can card. */ -class CanbusComponent final : public apollo::cybertron::TimerComponent { +class CanbusComponent final : public apollo::cyber::TimerComponent { public: CanbusComponent(); /** @@ -105,7 +105,7 @@ class CanbusComponent final : public apollo::cybertron::TimerComponent { std::shared_ptr> chassis_detail_writer_; }; -CYBERTRON_REGISTER_COMPONENT(CanbusComponent) +CYBER_REGISTER_COMPONENT(CanbusComponent) } // namespace canbus } // namespace apollo diff --git a/modules/canbus/launch/canbus.launch b/modules/canbus/launch/canbus.launch index 56941e0b36c..850740732ab 100644 --- a/modules/canbus/launch/canbus.launch +++ b/modules/canbus/launch/canbus.launch @@ -1,7 +1,7 @@ - + canbus /apollo/modules/canbus/dag/canbus.dag canbus - \ No newline at end of file + \ No newline at end of file diff --git a/modules/canbus/tools/BUILD b/modules/canbus/tools/BUILD index e4f67dfcdf2..1c9b959228b 100644 --- a/modules/canbus/tools/BUILD +++ b/modules/canbus/tools/BUILD @@ -11,7 +11,7 @@ cc_binary( "//modules/canbus/common:canbus_common", "//modules/common", "//modules/common/adapters:adapter_gflags", - "//cybertron", + "//cyber", ], ) @@ -24,7 +24,7 @@ cc_binary( "//modules/canbus/proto:canbus_proto", "//modules/common", "//modules/control/proto:control_proto", - "//cybertron", + "//cyber", ], ) diff --git a/modules/canbus/tools/canbus_tester.cc b/modules/canbus/tools/canbus_tester.cc index 04fa4f0fee9..93553f80e1d 100644 --- a/modules/canbus/tools/canbus_tester.cc +++ b/modules/canbus/tools/canbus_tester.cc @@ -16,30 +16,30 @@ #include -#include "cybertron/cybertron.h" -#include "cybertron/time/rate.h" +#include "cyber/cyber.h" +#include "cyber/time/rate.h" #include "gflags/gflags.h" #include "modules/canbus/common/canbus_gflags.h" #include "modules/common/adapters/adapter_gflags.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/file.h" #include "modules/control/proto/control_cmd.pb.h" using apollo::control::ControlCommand; -using apollo::cybertron::Rate; -using apollo::cybertron::Reader; -using apollo::cybertron::Writer; +using apollo::cyber::Rate; +using apollo::cyber::Reader; +using apollo::cyber::Writer; int main(int32_t argc, char **argv) { google::InitGoogleLogging(argv[0]); google::ParseCommandLineFlags(&argc, &argv, true); FLAGS_alsologtostderr = true; - // init cybertron framework - apollo::cybertron::Init("testing_canbus_tester"); - std::shared_ptr node_( - apollo::cybertron::CreateNode("canbus_tester")); + // init cyber framework + apollo::cyber::Init("testing_canbus_tester"); + std::shared_ptr node_( + apollo::cyber::CreateNode("canbus_tester")); std::shared_ptr> control_command_writer_ = node_->CreateWriter(FLAGS_control_command_topic); @@ -52,7 +52,7 @@ int main(int32_t argc, char **argv) { Rate rate(1.0); // frequency - while (apollo::cybertron::OK()) { + while (apollo::cyber::OK()) { // pub.publish(msg); control_command_writer_->Write( std::make_shared(control_cmd)); diff --git a/modules/canbus/tools/teleop.cc b/modules/canbus/tools/teleop.cc index 7ecaae62be4..07995e652e2 100644 --- a/modules/canbus/tools/teleop.cc +++ b/modules/canbus/tools/teleop.cc @@ -20,14 +20,14 @@ #include #include -#include "cybertron/common/macros.h" -#include "cybertron/cybertron.h" -#include "cybertron/time/time.h" +#include "cyber/common/macros.h" +#include "cyber/cyber.h" +#include "cyber/time/time.h" #include "modules/canbus/proto/chassis.pb.h" #include "modules/control/proto/control_cmd.pb.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/adapters/adapter_gflags.h" #include "modules/common/time/time.h" #include "modules/common/util/message_util.h" @@ -45,9 +45,9 @@ using apollo::common::VehicleSignal; using apollo::common::time::Clock; using apollo::control::ControlCommand; using apollo::control::PadMessage; -using apollo::cybertron::CreateNode; -using apollo::cybertron::Reader; -using apollo::cybertron::Writer; +using apollo::cyber::CreateNode; +using apollo::cyber::Reader; +using apollo::cyber::Writer; const uint32_t KEYCODE_O = 0x4F; // '0' @@ -409,13 +409,13 @@ class Teleop { std::shared_ptr> control_command_writer_; ControlCommand control_command_; bool is_running_ = false; - std::shared_ptr node_; + std::shared_ptr node_; }; } // namespace int main(int32_t argc, char **argv) { - apollo::cybertron::Init(argv[0]); + apollo::cyber::Init(argv[0]); FLAGS_alsologtostderr = true; FLAGS_v = 3; @@ -428,7 +428,7 @@ int main(int32_t argc, char **argv) { return -1; } Teleop::PrintKeycode(); - apollo::cybertron::WaitForShutdown(); + apollo::cyber::WaitForShutdown(); teleop.Stop(); AINFO << "Teleop exit done."; return 0; diff --git a/modules/canbus/vehicle/gem/gem_controller.cc b/modules/canbus/vehicle/gem/gem_controller.cc index 3036cd50f9c..e8613d12ac5 100644 --- a/modules/canbus/vehicle/gem/gem_controller.cc +++ b/modules/canbus/vehicle/gem/gem_controller.cc @@ -20,7 +20,7 @@ limitations under the License. #include "modules/canbus/vehicle/gem/gem_message_manager.h" #include "modules/canbus/vehicle/vehicle_controller.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/time/time.h" #include "modules/drivers/canbus/can_comm/can_sender.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" diff --git a/modules/canbus/vehicle/gem/gem_controller.h b/modules/canbus/vehicle/gem/gem_controller.h index b74dcf97e46..668a8e1ff11 100644 --- a/modules/canbus/vehicle/gem/gem_controller.h +++ b/modules/canbus/vehicle/gem/gem_controller.h @@ -19,7 +19,7 @@ #include #include -#include "cybertron/common/macros.h" +#include "cyber/common/macros.h" #include "modules/canbus/proto/canbus_conf.pb.h" #include "modules/canbus/proto/chassis.pb.h" diff --git a/modules/canbus/vehicle/gem/gem_vehicle_factory.cc b/modules/canbus/vehicle/gem/gem_vehicle_factory.cc index 23bbf805416..046962b689e 100644 --- a/modules/canbus/vehicle/gem/gem_vehicle_factory.cc +++ b/modules/canbus/vehicle/gem/gem_vehicle_factory.cc @@ -18,7 +18,7 @@ #include "modules/canbus/vehicle/gem/gem_controller.h" #include "modules/canbus/vehicle/gem/gem_message_manager.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/util.h" namespace apollo { diff --git a/modules/canbus/vehicle/lexus/lexus_controller.cc b/modules/canbus/vehicle/lexus/lexus_controller.cc index 7015bc6fb05..ba59a44fd29 100644 --- a/modules/canbus/vehicle/lexus/lexus_controller.cc +++ b/modules/canbus/vehicle/lexus/lexus_controller.cc @@ -15,7 +15,7 @@ limitations under the License. #include "modules/canbus/vehicle/lexus/lexus_controller.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/canbus/vehicle/lexus/lexus_message_manager.h" #include "modules/canbus/vehicle/vehicle_controller.h" #include "modules/common/proto/vehicle_signal.pb.h" diff --git a/modules/canbus/vehicle/lexus/lexus_vehicle_factory.cc b/modules/canbus/vehicle/lexus/lexus_vehicle_factory.cc index e32930fd521..cb5f3c86805 100644 --- a/modules/canbus/vehicle/lexus/lexus_vehicle_factory.cc +++ b/modules/canbus/vehicle/lexus/lexus_vehicle_factory.cc @@ -16,7 +16,7 @@ #include "modules/canbus/vehicle/lexus/lexus_vehicle_factory.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/canbus/vehicle/lexus/lexus_controller.h" #include "modules/canbus/vehicle/lexus/lexus_message_manager.h" #include "modules/common/util/util.h" diff --git a/modules/canbus/vehicle/lincoln/lincoln_controller.cc b/modules/canbus/vehicle/lincoln/lincoln_controller.cc index bdd9aa10325..3821cced513 100644 --- a/modules/canbus/vehicle/lincoln/lincoln_controller.cc +++ b/modules/canbus/vehicle/lincoln/lincoln_controller.cc @@ -26,7 +26,7 @@ #include "modules/canbus/vehicle/lincoln/protocol/turnsignal_68.h" #include "modules/canbus/vehicle/vehicle_controller.h" #include "modules/common/kv_db/kv_db.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/time/time.h" #include "modules/drivers/canbus/can_comm/can_sender.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" diff --git a/modules/canbus/vehicle/lincoln/lincoln_controller.h b/modules/canbus/vehicle/lincoln/lincoln_controller.h index 239b5be5458..d2c79edcfa1 100644 --- a/modules/canbus/vehicle/lincoln/lincoln_controller.h +++ b/modules/canbus/vehicle/lincoln/lincoln_controller.h @@ -26,7 +26,7 @@ #include "gtest/gtest_prod.h" -#include "cybertron/common/macros.h" +#include "cyber/common/macros.h" #include "modules/canbus/proto/canbus_conf.pb.h" #include "modules/canbus/proto/chassis.pb.h" diff --git a/modules/canbus/vehicle/lincoln/lincoln_vehicle_factory.cc b/modules/canbus/vehicle/lincoln/lincoln_vehicle_factory.cc index f9255f32f34..31f57cc7f92 100644 --- a/modules/canbus/vehicle/lincoln/lincoln_vehicle_factory.cc +++ b/modules/canbus/vehicle/lincoln/lincoln_vehicle_factory.cc @@ -18,7 +18,7 @@ #include "modules/canbus/vehicle/lincoln/lincoln_controller.h" #include "modules/canbus/vehicle/lincoln/lincoln_message_manager.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/util.h" namespace apollo { diff --git a/modules/canbus/vehicle/vehicle_controller.cc b/modules/canbus/vehicle/vehicle_controller.cc index 4aada0bb0f7..1a1305c26af 100644 --- a/modules/canbus/vehicle/vehicle_controller.cc +++ b/modules/canbus/vehicle/vehicle_controller.cc @@ -16,7 +16,7 @@ #include "modules/canbus/vehicle/vehicle_controller.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace canbus { diff --git a/modules/common/BUILD b/modules/common/BUILD index 4e767998ada..aa5320996b6 100644 --- a/modules/common/BUILD +++ b/modules/common/BUILD @@ -5,7 +5,7 @@ package(default_visibility = ["//visibility:public"]) cc_library( name = "common", deps = [ - "//cybertron", + "//cyber", "//modules/common/math", "//modules/common/status", "//modules/common/util", diff --git a/modules/common/configs/BUILD b/modules/common/configs/BUILD index c351b3aed19..6b638d179d8 100644 --- a/modules/common/configs/BUILD +++ b/modules/common/configs/BUILD @@ -31,7 +31,7 @@ cc_library( ], deps = [ ":config_gflags", - "//cybertron", + "//cyber", "//modules/common", "//modules/common/configs/proto:vehicle_config_proto", "//modules/common/util", diff --git a/modules/common/configs/config_gflags.cc b/modules/common/configs/config_gflags.cc index 61f4bd3347b..7c42d64f228 100644 --- a/modules/common/configs/config_gflags.cc +++ b/modules/common/configs/config_gflags.cc @@ -38,9 +38,9 @@ DEFINE_string(vehicle_config_path, "/apollo/modules/common/data/mkz_config.pb.txt", "the file path of vehicle config file"); -DEFINE_bool(use_cybertron_time, false, +DEFINE_bool(use_cyber_time, false, "Whether Clock::Now() gets time from system_clock::now() or from " - "Cybertron."); + "Cyber."); DEFINE_string(localization_tf2_frame_id, "world", "the tf2 transform frame id"); DEFINE_string(localization_tf2_child_frame_id, "localization", diff --git a/modules/common/configs/config_gflags.h b/modules/common/configs/config_gflags.h index 7826c1307c2..a50ea05c319 100644 --- a/modules/common/configs/config_gflags.h +++ b/modules/common/configs/config_gflags.h @@ -34,7 +34,7 @@ DECLARE_double(look_forward_time_sec); DECLARE_string(vehicle_config_path); -DECLARE_bool(use_cybertron_time); +DECLARE_bool(use_cyber_time); DECLARE_string(localization_tf2_frame_id); DECLARE_string(localization_tf2_child_frame_id); diff --git a/modules/common/configs/vehicle_config_helper.h b/modules/common/configs/vehicle_config_helper.h index f517f662e66..cf74c34e38f 100644 --- a/modules/common/configs/vehicle_config_helper.h +++ b/modules/common/configs/vehicle_config_helper.h @@ -22,7 +22,7 @@ #include -#include "cybertron/common/macros.h" +#include "cyber/common/macros.h" #include "modules/common/configs/proto/vehicle_config.pb.h" diff --git a/modules/common/filters/BUILD b/modules/common/filters/BUILD index 2036c5ac483..dd9dcb7d322 100644 --- a/modules/common/filters/BUILD +++ b/modules/common/filters/BUILD @@ -12,7 +12,7 @@ cc_library( ], deps = [ ":digital_filter_coefficients", - "//cybertron", + "//cyber", ], ) @@ -25,7 +25,7 @@ cc_library( "mean_filter.h", ], deps = [ - "//cybertron", + "//cyber", ], ) @@ -59,7 +59,7 @@ cc_test( ":digital_filter_coefficients", "//modules/common", "@gtest//:main", - "//cybertron", + "//cyber", ], ) diff --git a/modules/common/filters/digital_filter.cc b/modules/common/filters/digital_filter.cc index 08fe04c97e6..065a07dc174 100644 --- a/modules/common/filters/digital_filter.cc +++ b/modules/common/filters/digital_filter.cc @@ -18,7 +18,7 @@ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace { diff --git a/modules/common/filters/mean_filter.cc b/modules/common/filters/mean_filter.cc index 846ddac0831..b1deeeee54a 100644 --- a/modules/common/filters/mean_filter.cc +++ b/modules/common/filters/mean_filter.cc @@ -18,7 +18,7 @@ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace common { diff --git a/modules/common/kv_db/BUILD b/modules/common/kv_db/BUILD index ef147f71b29..87dc8e92b93 100644 --- a/modules/common/kv_db/BUILD +++ b/modules/common/kv_db/BUILD @@ -15,7 +15,7 @@ cc_library( ], deps = [ "//external:gflags", - "//cybertron", + "//cyber", "//modules/common/util", ], ) diff --git a/modules/common/kv_db/kv_db.cc b/modules/common/kv_db/kv_db.cc index 147062fcc8b..339ebf96da0 100644 --- a/modules/common/kv_db/kv_db.cc +++ b/modules/common/kv_db/kv_db.cc @@ -18,7 +18,7 @@ #include #include "gflags/gflags.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/file.h" #include "modules/common/util/util.h" diff --git a/modules/common/kv_db/kv_db_tool.cc b/modules/common/kv_db/kv_db_tool.cc index 85d7a467c7e..f877c86cdf5 100644 --- a/modules/common/kv_db/kv_db_tool.cc +++ b/modules/common/kv_db/kv_db_tool.cc @@ -18,7 +18,7 @@ #include #include "gflags/gflags.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" DEFINE_string(op, "get", "Operation to execute, should be put, get or del."); DEFINE_string(key, "", "The key to query."); diff --git a/modules/common/math/BUILD b/modules/common/math/BUILD index 5694b38b742..0770a771924 100644 --- a/modules/common/math/BUILD +++ b/modules/common/math/BUILD @@ -41,7 +41,7 @@ cc_library( "vec2d.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/common/util:string_util", "@osqp", ], @@ -103,7 +103,7 @@ cc_library( "matrix_operations.h", ], deps = [ - "//cybertron", + "//cyber", "@eigen", ], ) @@ -126,7 +126,7 @@ cc_library( "kalman_filter.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/common/math:matrix_operations", "@eigen", ], @@ -138,7 +138,7 @@ cc_library( "extended_kalman_filter.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/common/math:matrix_operations", "@eigen", ], @@ -230,7 +230,7 @@ cc_library( "integral.h", ], deps = [ - "//cybertron", + "//cyber", ], ) @@ -243,7 +243,7 @@ cc_library( "linear_quadratic_regulator.h", ], deps = [ - "//cybertron", + "//cyber", "@eigen", ], ) @@ -257,7 +257,7 @@ cc_library( "mpc_solver.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/common/math/qp_solver", "//modules/common/math/qp_solver:active_set_qp_solver", "@eigen", @@ -274,7 +274,7 @@ cc_library( ], deps = [ ":geometry", - "//cybertron", + "//cyber", "@eigen", ], ) @@ -285,7 +285,7 @@ cc_library( "hermite_spline.h", ], deps = [ - "//cybertron", + "//cyber", ], ) @@ -323,7 +323,7 @@ cc_test( ], deps = [ ":linear_interpolation", - "//cybertron", + "//cyber", "@eigen", "@gtest//:main", ], diff --git a/modules/common/math/aabox2d.cc b/modules/common/math/aabox2d.cc index d374c2631e6..cbe0fc61618 100644 --- a/modules/common/math/aabox2d.cc +++ b/modules/common/math/aabox2d.cc @@ -19,7 +19,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/string_util.h" #include "modules/common/math/math_utils.h" diff --git a/modules/common/math/aaboxkdtree2d.h b/modules/common/math/aaboxkdtree2d.h index 114e10ec974..e1bbc262cf6 100644 --- a/modules/common/math/aaboxkdtree2d.h +++ b/modules/common/math/aaboxkdtree2d.h @@ -26,7 +26,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/math/aabox2d.h" #include "modules/common/math/math_utils.h" diff --git a/modules/common/math/box2d.cc b/modules/common/math/box2d.cc index 86887381ac0..0a6f7f11bdc 100644 --- a/modules/common/math/box2d.cc +++ b/modules/common/math/box2d.cc @@ -20,7 +20,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/string_util.h" #include "modules/common/math/math_utils.h" diff --git a/modules/common/math/cartesian_frenet_conversion.cc b/modules/common/math/cartesian_frenet_conversion.cc index 92518b88731..b8601ebccc7 100644 --- a/modules/common/math/cartesian_frenet_conversion.cc +++ b/modules/common/math/cartesian_frenet_conversion.cc @@ -18,7 +18,7 @@ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/math/math_utils.h" namespace apollo { diff --git a/modules/common/math/extended_kalman_filter.h b/modules/common/math/extended_kalman_filter.h index 5c4bbe0c995..32ce4461a16 100644 --- a/modules/common/math/extended_kalman_filter.h +++ b/modules/common/math/extended_kalman_filter.h @@ -25,7 +25,7 @@ #include #include "Eigen/Dense" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/math/matrix_operations.h" /** diff --git a/modules/common/math/hermite_spline.h b/modules/common/math/hermite_spline.h index 2ab056ffacd..5afa52e4986 100644 --- a/modules/common/math/hermite_spline.h +++ b/modules/common/math/hermite_spline.h @@ -23,7 +23,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace common { diff --git a/modules/common/math/integral.cc b/modules/common/math/integral.cc index f2b5d3bafd3..bee200daf98 100644 --- a/modules/common/math/integral.cc +++ b/modules/common/math/integral.cc @@ -18,7 +18,7 @@ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace common { diff --git a/modules/common/math/kalman_filter.h b/modules/common/math/kalman_filter.h index d1e25e9f6a1..8094f658c75 100644 --- a/modules/common/math/kalman_filter.h +++ b/modules/common/math/kalman_filter.h @@ -26,7 +26,7 @@ #include "Eigen/Dense" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/math/matrix_operations.h" /** diff --git a/modules/common/math/line_segment2d.cc b/modules/common/math/line_segment2d.cc index fbae68efba0..e24169d2a15 100644 --- a/modules/common/math/line_segment2d.cc +++ b/modules/common/math/line_segment2d.cc @@ -20,7 +20,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/string_util.h" #include "modules/common/math/math_utils.h" diff --git a/modules/common/math/linear_interpolation.cc b/modules/common/math/linear_interpolation.cc index 80213cb87bd..6d6ad9c496d 100644 --- a/modules/common/math/linear_interpolation.cc +++ b/modules/common/math/linear_interpolation.cc @@ -18,7 +18,7 @@ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/math/math_utils.h" namespace apollo { diff --git a/modules/common/math/linear_interpolation.h b/modules/common/math/linear_interpolation.h index 71d07420960..f535d7801f9 100644 --- a/modules/common/math/linear_interpolation.h +++ b/modules/common/math/linear_interpolation.h @@ -23,7 +23,7 @@ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/proto/pnc_point.pb.h" /** diff --git a/modules/common/math/linear_quadratic_regulator.cc b/modules/common/math/linear_quadratic_regulator.cc index 5dd927d5076..0e8edba056c 100644 --- a/modules/common/math/linear_quadratic_regulator.cc +++ b/modules/common/math/linear_quadratic_regulator.cc @@ -18,7 +18,7 @@ #include "Eigen/Dense" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/math/linear_quadratic_regulator.h" namespace apollo { diff --git a/modules/common/math/matrix_operations.h b/modules/common/math/matrix_operations.h index 09c25e60f82..8678b61ef1c 100644 --- a/modules/common/math/matrix_operations.h +++ b/modules/common/math/matrix_operations.h @@ -28,7 +28,7 @@ #include "Eigen/Dense" #include "Eigen/SVD" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" /** * @namespace apollo::common::math diff --git a/modules/common/math/mpc_solver.cc b/modules/common/math/mpc_solver.cc index 98dc810fe8f..458a9624e41 100644 --- a/modules/common/math/mpc_solver.cc +++ b/modules/common/math/mpc_solver.cc @@ -17,7 +17,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/math/qp_solver/active_set_qp_solver.h" #include "modules/common/math/qp_solver/qp_solver.h" diff --git a/modules/common/math/nonlinear_interpolation.cc b/modules/common/math/nonlinear_interpolation.cc index ea70edcd94f..84d8ba909b6 100644 --- a/modules/common/math/nonlinear_interpolation.cc +++ b/modules/common/math/nonlinear_interpolation.cc @@ -17,7 +17,7 @@ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/math/hermite_spline.h" #include "modules/common/math/integral.h" #include "modules/common/math/math_utils.h" diff --git a/modules/common/math/polygon2d.cc b/modules/common/math/polygon2d.cc index 4dd312533b4..e3905773ca5 100644 --- a/modules/common/math/polygon2d.cc +++ b/modules/common/math/polygon2d.cc @@ -21,7 +21,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/math/math_utils.h" #include "modules/common/util/string_util.h" diff --git a/modules/common/math/qp_solver/BUILD b/modules/common/math/qp_solver/BUILD index e67cf574d0f..48e620b0c5b 100644 --- a/modules/common/math/qp_solver/BUILD +++ b/modules/common/math/qp_solver/BUILD @@ -39,7 +39,7 @@ cc_library( linkstatic = False, deps = [ ":qp_solver", - "//cybertron", + "//cyber", "//modules/common/math/qp_solver:qp_solver_gflags", "@eigen", "@qpOASES", diff --git a/modules/common/math/qp_solver/active_set_qp_solver.cc b/modules/common/math/qp_solver/active_set_qp_solver.cc index cc72b610851..7fd656916af 100644 --- a/modules/common/math/qp_solver/active_set_qp_solver.cc +++ b/modules/common/math/qp_solver/active_set_qp_solver.cc @@ -23,7 +23,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/math/qp_solver/qp_solver_gflags.h" namespace apollo { diff --git a/modules/common/math/vec2d.cc b/modules/common/math/vec2d.cc index 264a12092ad..bb48c9624d9 100644 --- a/modules/common/math/vec2d.cc +++ b/modules/common/math/vec2d.cc @@ -18,7 +18,7 @@ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/string_util.h" namespace apollo { diff --git a/modules/common/monitor_log/BUILD b/modules/common/monitor_log/BUILD index d135fda461e..3145c89e569 100644 --- a/modules/common/monitor_log/BUILD +++ b/modules/common/monitor_log/BUILD @@ -13,8 +13,8 @@ cc_library( "monitor_logger.h", ], deps = [ - "//cybertron", - "//cybertron/proto:component_config_cc_proto", + "//cyber", + "//cyber/proto:component_config_cc_proto", "//modules/common/monitor_log/proto:monitor_log_proto", "//modules/common/proto:geometry_proto", "//modules/common/time", diff --git a/modules/common/monitor_log/monitor_log_buffer.cc b/modules/common/monitor_log/monitor_log_buffer.cc index ae757f60db6..ca8ae312dd0 100644 --- a/modules/common/monitor_log/monitor_log_buffer.cc +++ b/modules/common/monitor_log/monitor_log_buffer.cc @@ -16,7 +16,7 @@ #include "modules/common/monitor_log/monitor_log_buffer.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/monitor_log/monitor_logger.h" namespace apollo { diff --git a/modules/common/monitor_log/monitor_log_buffer_test.cc b/modules/common/monitor_log/monitor_log_buffer_test.cc index e485e8bc560..96c50875288 100644 --- a/modules/common/monitor_log/monitor_log_buffer_test.cc +++ b/modules/common/monitor_log/monitor_log_buffer_test.cc @@ -21,7 +21,7 @@ #include "gtest/gtest.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace common { @@ -29,7 +29,7 @@ namespace monitor { class MonitorBufferTest : public ::testing::Test { protected: - void SetUp() override { cybertron::Init(); } + void SetUp() override { cyber::Init(); } void TearDown() override {} MonitorLogBuffer buffer_{MonitorMessageItem::CONTROL}; }; diff --git a/modules/common/monitor_log/monitor_logger.cc b/modules/common/monitor_log/monitor_logger.cc index faaecc2f4b5..5be8f48f665 100644 --- a/modules/common/monitor_log/monitor_logger.cc +++ b/modules/common/monitor_log/monitor_logger.cc @@ -23,8 +23,8 @@ namespace monitor { MonitorLogger::MonitorLogger() { auto node_name = - "monitor_logger" + std::to_string(cybertron::Time::Now().ToNanosecond()); - node_ = cybertron::CreateNode(node_name); + "monitor_logger" + std::to_string(cyber::Time::Now().ToNanosecond()); + node_ = cyber::CreateNode(node_name); if (node_ != nullptr) { monitor_msg_writer_ = node_->CreateWriter("/apollo/monitor"); diff --git a/modules/common/monitor_log/monitor_logger.h b/modules/common/monitor_log/monitor_logger.h index d11fd1b03d6..564494636ab 100644 --- a/modules/common/monitor_log/monitor_logger.h +++ b/modules/common/monitor_log/monitor_logger.h @@ -26,7 +26,7 @@ #include #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/common/util/message_util.h" #include "modules/common/monitor_log/proto/monitor_log.pb.h" @@ -39,8 +39,8 @@ namespace common { namespace monitor { using MessageItem = std::pair; -using apollo::cybertron::Node; -using apollo::cybertron::Writer; +using apollo::cyber::Node; +using apollo::cyber::Writer; /** * class MonitorLogger diff --git a/modules/common/time/BUILD b/modules/common/time/BUILD index 1be4fb03073..0482c9b511b 100644 --- a/modules/common/time/BUILD +++ b/modules/common/time/BUILD @@ -13,7 +13,7 @@ cc_library( "timer.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/common/configs:config_gflags", ], ) diff --git a/modules/common/time/time.h b/modules/common/time/time.h index 64e5cfd9236..672ceb7659d 100644 --- a/modules/common/time/time.h +++ b/modules/common/time/time.h @@ -28,10 +28,10 @@ #include #include -#include "cybertron/common/macros.h" -#include "cybertron/time/time.h" +#include "cyber/common/macros.h" +#include "cyber/time/time.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/configs/config_gflags.h" /** @@ -152,7 +152,7 @@ class Clock { enum ClockMode { SYSTEM = 0, MOCK = 1, - CYBERTRON = 2, + CYBER = 2, }; /** @@ -165,12 +165,12 @@ class Clock { return SystemNow(); case ClockMode::MOCK: return Instance()->mock_now_; - case ClockMode::CYBERTRON: - return From(cybertron::Time::Now().ToSecond()); + case ClockMode::CYBER: + return From(cyber::Time::Now().ToSecond()); default: AFATAL << "Unsupported clock mode: " << mode(); } - return From(cybertron::Time::Now().ToSecond()); + return From(cyber::Time::Now().ToSecond()); } /** @@ -250,7 +250,7 @@ class Clock { }; inline Clock::Clock() - : Clock(FLAGS_use_cybertron_time ? ClockMode::CYBERTRON + : Clock(FLAGS_use_cyber_time ? ClockMode::CYBER : ClockMode::SYSTEM) {} // Measure run time of a code block, mostly for debugging purpose. diff --git a/modules/common/time/time_util.h b/modules/common/time/time_util.h index 130ed776c6d..e198736eb6a 100644 --- a/modules/common/time/time_util.h +++ b/modules/common/time/time_util.h @@ -19,7 +19,7 @@ #include #include -#include "cybertron/common/macros.h" +#include "cyber/common/macros.h" namespace apollo { namespace common { diff --git a/modules/common/time/timer.cc b/modules/common/time/timer.cc index c542a219c85..0e9bedde137 100644 --- a/modules/common/time/timer.cc +++ b/modules/common/time/timer.cc @@ -16,7 +16,7 @@ #include "modules/common/time/timer.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/time/time.h" namespace apollo { diff --git a/modules/common/time/timer.h b/modules/common/time/timer.h index a695b1b263e..d0653d3808c 100644 --- a/modules/common/time/timer.h +++ b/modules/common/time/timer.h @@ -20,7 +20,7 @@ #include #include -#include "cybertron/common/macros.h" +#include "cyber/common/macros.h" namespace apollo { namespace common { diff --git a/modules/common/time/timer_test.cc b/modules/common/time/timer_test.cc index bf9a02b8bf8..44eabad2c6a 100644 --- a/modules/common/time/timer_test.cc +++ b/modules/common/time/timer_test.cc @@ -19,7 +19,7 @@ #include #include "gtest/gtest.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace common { diff --git a/modules/common/util/BUILD b/modules/common/util/BUILD index e408b5f1b03..22f245f88bf 100644 --- a/modules/common/util/BUILD +++ b/modules/common/util/BUILD @@ -55,7 +55,7 @@ cc_test( ], deps = [ ":disjoint_set", - "//cybertron", + "//cyber", "@gtest//:main", ], ) @@ -149,7 +149,7 @@ cc_library( "factory.h", ], deps = [ - "//cybertron", + "//cyber", ], ) @@ -161,7 +161,7 @@ cc_test( ], deps = [ ":factory", - "//cybertron", + "//cyber", "//modules/common", "@gtest//:main", ], @@ -181,7 +181,7 @@ cc_library( ], deps = [ ":string_util", - "//cybertron", + "//cyber", "@com_google_protobuf//:protobuf", ], ) @@ -223,7 +223,7 @@ cc_library( "points_downsampler.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/common/math:geometry", ], ) @@ -249,7 +249,7 @@ cc_library( "json_util.h", ], deps = [ - "//cybertron", + "//cyber", "//third_party/json", "@com_google_protobuf//:protobuf", ], @@ -273,7 +273,7 @@ cc_library( srcs = ["http_client.cc"], hdrs = ["http_client.h"], deps = [ - "//cybertron", + "//cyber", "//modules/common/status", "//modules/common/util:string_util", "//third_party/json", diff --git a/modules/common/util/blocking_queue.h b/modules/common/util/blocking_queue.h index 4716931198b..6ee67623f90 100644 --- a/modules/common/util/blocking_queue.h +++ b/modules/common/util/blocking_queue.h @@ -23,7 +23,7 @@ #include "boost/date_time/posix_time/posix_time.hpp" #include "boost/thread.hpp" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace common { diff --git a/modules/common/util/disjoint_set_test.cc b/modules/common/util/disjoint_set_test.cc index 9aaa0ea942a..88cd54026f5 100644 --- a/modules/common/util/disjoint_set_test.cc +++ b/modules/common/util/disjoint_set_test.cc @@ -17,7 +17,7 @@ #include "modules/common/util/disjoint_set.h" #include "gtest/gtest.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace common { diff --git a/modules/common/util/factory.h b/modules/common/util/factory.h index 0803f1c6a38..35a18a52454 100644 --- a/modules/common/util/factory.h +++ b/modules/common/util/factory.h @@ -25,9 +25,9 @@ #include #include -#include "cybertron/common/macros.h" +#include "cyber/common/macros.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" /** * @namespace apollo::common::util diff --git a/modules/common/util/file.h b/modules/common/util/file.h index 1c1e8ac1f10..3a983b18050 100644 --- a/modules/common/util/file.h +++ b/modules/common/util/file.h @@ -33,7 +33,7 @@ #include "google/protobuf/io/zero_copy_stream_impl.h" #include "google/protobuf/text_format.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/string_util.h" /** diff --git a/modules/common/util/file_test.cc b/modules/common/util/file_test.cc index 826ccd8ca61..9a5a2cecf7b 100644 --- a/modules/common/util/file_test.cc +++ b/modules/common/util/file_test.cc @@ -17,7 +17,7 @@ #include "modules/common/util/file.h" #include "boost/filesystem.hpp" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "gmock/gmock.h" #include "gtest/gtest.h" #include "modules/common/util/testdata/simple.pb.h" diff --git a/modules/common/util/http_client.cc b/modules/common/util/http_client.cc index 36d28c100bf..baaf87c4439 100644 --- a/modules/common/util/http_client.cc +++ b/modules/common/util/http_client.cc @@ -21,7 +21,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/string_util.h" namespace apollo { diff --git a/modules/common/util/json_util.h b/modules/common/util/json_util.h index e7ad2339665..07aca8b7f4f 100644 --- a/modules/common/util/json_util.h +++ b/modules/common/util/json_util.h @@ -22,7 +22,7 @@ #include "google/protobuf/message.h" #include "third_party/json/json.hpp" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace common { diff --git a/modules/common/util/points_downsampler.h b/modules/common/util/points_downsampler.h index 8ab1fb0d13e..42aa133ca52 100644 --- a/modules/common/util/points_downsampler.h +++ b/modules/common/util/points_downsampler.h @@ -23,7 +23,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/math/vec2d.h" /** diff --git a/modules/common/vehicle_state/BUILD b/modules/common/vehicle_state/BUILD index 794592bcb4c..d3ab1f112fe 100644 --- a/modules/common/vehicle_state/BUILD +++ b/modules/common/vehicle_state/BUILD @@ -11,7 +11,7 @@ cc_library( "vehicle_state_provider.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/common/configs:config_gflags", "//modules/common/math:geometry", "//modules/common/math:quaternion", diff --git a/modules/common/vehicle_state/vehicle_state_provider.cc b/modules/common/vehicle_state/vehicle_state_provider.cc index c7f4deac6cb..41f4d1c462e 100644 --- a/modules/common/vehicle_state/vehicle_state_provider.cc +++ b/modules/common/vehicle_state/vehicle_state_provider.cc @@ -20,7 +20,7 @@ #include "Eigen/Core" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/configs/config_gflags.h" #include "modules/common/math/euler_angles_zxy.h" diff --git a/modules/common/vehicle_state/vehicle_state_provider.h b/modules/common/vehicle_state/vehicle_state_provider.h index 66cc3359322..d6acaeed0d7 100644 --- a/modules/common/vehicle_state/vehicle_state_provider.h +++ b/modules/common/vehicle_state/vehicle_state_provider.h @@ -23,7 +23,7 @@ #include #include -#include "cybertron/common/macros.h" +#include "cyber/common/macros.h" #include "modules/canbus/proto/chassis.pb.h" #include "modules/common/vehicle_state/proto/vehicle_state.pb.h" diff --git a/modules/control/BUILD b/modules/control/BUILD index 53c1a1da97e..c368b200b3b 100644 --- a/modules/control/BUILD +++ b/modules/control/BUILD @@ -20,7 +20,7 @@ cc_library( "//modules/perception/proto:perception_proto", "//modules/planning/proto:planning_proto", "//modules/prediction/proto:prediction_proto", - "//cybertron", + "//cyber", "//external:gflags", ], ) diff --git a/modules/control/common/BUILD b/modules/control/common/BUILD index 382888e5e83..805914e0360 100644 --- a/modules/control/common/BUILD +++ b/modules/control/common/BUILD @@ -34,7 +34,7 @@ cc_library( "interpolation_1d.h", ], deps = [ - "//cybertron", + "//cyber", "@eigen//:eigen", ], ) @@ -48,7 +48,7 @@ cc_library( "interpolation_2d.h", ], deps = [ - "//cybertron", + "//cyber", "@eigen//:eigen", ], ) @@ -62,7 +62,7 @@ cc_library( "pid_controller.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/control/proto:control_proto", ], ) @@ -77,7 +77,7 @@ cc_library( ], deps = [ ":pid_controller", - "//cybertron", + "//cyber", "//modules/common/math", "//modules/control/proto:control_proto", ], @@ -93,7 +93,7 @@ cc_library( ], deps = [ ":pid_controller", - "//cybertron", + "//cyber", "//modules/common/math", "//modules/control/proto:control_proto", ], @@ -108,7 +108,7 @@ cc_library( "trajectory_analyzer.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/common/math:linear_interpolation", "//modules/common/math:search", "//modules/common/proto:pnc_point_proto", @@ -150,7 +150,7 @@ cc_test( data = ["//modules/control/testdata:control_testdata"], deps = [ ":interpolation_1d", - "//cybertron", + "//cyber", "//modules/common/util", "//modules/control/proto:control_proto", "@gtest//:main", @@ -166,7 +166,7 @@ cc_test( data = ["//modules/control/testdata:control_testdata"], deps = [ ":interpolation_2d", - "//cybertron", + "//cyber", "//modules/common/util", "//modules/control/proto:control_proto", "@gtest//:main", diff --git a/modules/control/common/interpolation_1d.cc b/modules/control/common/interpolation_1d.cc index 356545d7440..29451b02dc9 100644 --- a/modules/control/common/interpolation_1d.cc +++ b/modules/control/common/interpolation_1d.cc @@ -17,7 +17,7 @@ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace control { diff --git a/modules/control/common/interpolation_1d_test.cc b/modules/control/common/interpolation_1d_test.cc index 572b12d56b2..6f868a5f9c8 100644 --- a/modules/control/common/interpolation_1d_test.cc +++ b/modules/control/common/interpolation_1d_test.cc @@ -19,7 +19,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "gmock/gmock.h" #include "modules/common/util/file.h" #include "modules/control/proto/control_conf.pb.h" diff --git a/modules/control/common/interpolation_2d.cc b/modules/control/common/interpolation_2d.cc index d572e9c95dc..dd5f1c13efe 100644 --- a/modules/control/common/interpolation_2d.cc +++ b/modules/control/common/interpolation_2d.cc @@ -18,7 +18,7 @@ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace { diff --git a/modules/control/common/interpolation_2d_test.cc b/modules/control/common/interpolation_2d_test.cc index dfb71d757e0..9262f9cceeb 100644 --- a/modules/control/common/interpolation_2d_test.cc +++ b/modules/control/common/interpolation_2d_test.cc @@ -19,7 +19,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "gtest/gtest.h" #include "modules/common/util/file.h" #include "modules/control/proto/control_conf.pb.h" diff --git a/modules/control/common/pid_BC_controller.cc b/modules/control/common/pid_BC_controller.cc index 47087be6484..296bba39f4e 100644 --- a/modules/control/common/pid_BC_controller.cc +++ b/modules/control/common/pid_BC_controller.cc @@ -18,7 +18,7 @@ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/math/math_utils.h" diff --git a/modules/control/common/pid_IC_controller.cc b/modules/control/common/pid_IC_controller.cc index fc4d6badab6..a16e96c85a5 100644 --- a/modules/control/common/pid_IC_controller.cc +++ b/modules/control/common/pid_IC_controller.cc @@ -19,7 +19,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/math/math_utils.h" namespace apollo { diff --git a/modules/control/common/pid_controller.cc b/modules/control/common/pid_controller.cc index 47236282390..f8fe9647d09 100644 --- a/modules/control/common/pid_controller.cc +++ b/modules/control/common/pid_controller.cc @@ -18,7 +18,7 @@ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace control { diff --git a/modules/control/common/trajectory_analyzer.cc b/modules/control/common/trajectory_analyzer.cc index 0a53eb0d8f7..1aa66e17393 100644 --- a/modules/control/common/trajectory_analyzer.cc +++ b/modules/control/common/trajectory_analyzer.cc @@ -20,7 +20,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/math/linear_interpolation.h" #include "modules/common/math/math_utils.h" #include "modules/common/math/search.h" diff --git a/modules/control/common/trajectory_analyzer_test.cc b/modules/control/common/trajectory_analyzer_test.cc index fb3c0275c45..c905d3bf22b 100644 --- a/modules/control/common/trajectory_analyzer_test.cc +++ b/modules/control/common/trajectory_analyzer_test.cc @@ -20,7 +20,7 @@ #include #include "gtest/gtest.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/time/time.h" using apollo::common::PathPoint; diff --git a/modules/control/conf/control.conf b/modules/control/conf/control.conf index 81896fbe237..af9fa78de36 100644 --- a/modules/control/conf/control.conf +++ b/modules/control/conf/control.conf @@ -6,6 +6,6 @@ --enable_gain_scheduler --set_steer_limit=true --noenable_input_timestamp_check ---use_cybertron_time=false +--use_cyber_time=false --enable_slope_offset=false --enable_persistent_estop diff --git a/modules/control/control_component.cc b/modules/control/control_component.cc index 070a1cfc187..70b45084bd3 100644 --- a/modules/control/control_component.cc +++ b/modules/control/control_component.cc @@ -18,7 +18,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/adapters/adapter_gflags.h" #include "modules/common/time/time.h" #include "modules/common/util/file.h" @@ -60,7 +60,7 @@ bool ControlComponent::Init() { return false; } - cybertron::ReaderConfig chassis_reader_config; + cyber::ReaderConfig chassis_reader_config; chassis_reader_config.channel_name = FLAGS_chassis_topic; chassis_reader_config.pending_queue_size = FLAGS_chassis_pending_queue_size; @@ -68,7 +68,7 @@ bool ControlComponent::Init() { chassis_reader_config, nullptr); CHECK(chassis_reader_ != nullptr); - cybertron::ReaderConfig planning_reader_config; + cyber::ReaderConfig planning_reader_config; planning_reader_config.channel_name = FLAGS_planning_trajectory_topic; planning_reader_config.pending_queue_size = FLAGS_planning_pending_queue_size; @@ -76,7 +76,7 @@ bool ControlComponent::Init() { planning_reader_config, nullptr); CHECK(trajectory_reader_ != nullptr); - cybertron::ReaderConfig localization_reader_config; + cyber::ReaderConfig localization_reader_config; localization_reader_config.channel_name = FLAGS_localization_topic; localization_reader_config.pending_queue_size = FLAGS_localization_pending_queue_size; @@ -85,7 +85,7 @@ bool ControlComponent::Init() { localization_reader_config, nullptr); CHECK(localization_reader_ != nullptr); - cybertron::ReaderConfig pad_msg_reader_config; + cyber::ReaderConfig pad_msg_reader_config; pad_msg_reader_config.channel_name = FLAGS_pad_topic; pad_msg_reader_config.pending_queue_size = FLAGS_pad_msg_pending_queue_size; diff --git a/modules/control/control_component.h b/modules/control/control_component.h index dcbe654f351..3888af3ef11 100644 --- a/modules/control/control_component.h +++ b/modules/control/control_component.h @@ -21,8 +21,8 @@ #include #include -#include "cybertron/class_loader/class_loader.h" -#include "cybertron/component/timer_component.h" +#include "cyber/class_loader/class_loader.h" +#include "cyber/component/timer_component.h" #include "modules/canbus/proto/chassis.pb.h" #include "modules/common/monitor_log/monitor_log_buffer.h" @@ -42,15 +42,15 @@ namespace apollo { namespace control { -using apollo::cybertron::Reader; -using apollo::cybertron::Writer; +using apollo::cyber::Reader; +using apollo::cyber::Writer; /** * @class Control * * @brief control module main class, it processes localization, chasiss, and * pad data to compute throttle, brake and steer values. */ -class ControlComponent final : public apollo::cybertron::TimerComponent { +class ControlComponent final : public apollo::cyber::TimerComponent { friend class ControlTestBase; public: @@ -122,6 +122,6 @@ class ControlComponent final : public apollo::cybertron::TimerComponent { LocalView local_view_; }; -CYBERTRON_REGISTER_COMPONENT(ControlComponent) +CYBER_REGISTER_COMPONENT(ControlComponent) } // namespace control } // namespace apollo diff --git a/modules/control/control_component_test.cc b/modules/control/control_component_test.cc index aa972e1351e..fe403134ba8 100644 --- a/modules/control/control_component_test.cc +++ b/modules/control/control_component_test.cc @@ -19,8 +19,8 @@ #include #include -#include "cybertron/common/log.h" -#include "cybertron/cybertron.h" +#include "cyber/common/log.h" +#include "cyber/cyber.h" #include "gtest/gtest.h" #include "modules/common/adapters/adapter_gflags.h" @@ -30,9 +30,9 @@ namespace apollo { namespace control { -using apollo::cybertron::ComponentConfig; -using apollo::cybertron::Reader; -using apollo::cybertron::Writer; +using apollo::cyber::ComponentConfig; +using apollo::cyber::Reader; +using apollo::cyber::Writer; using apollo::canbus::Chassis; using apollo::common::monitor::MonitorMessage; @@ -58,21 +58,21 @@ class ControlComponentTest : public ::testing::Test { "/apollo/modules/control/testdata/conf/lincoln.pb.txt"; FLAGS_is_control_test_mode = true; - SetupCybertron(); + SetupCyber(); } protected: bool FeedTestData(); - void SetupCybertron(); + void SetupCyber(); bool RunControl(const std::string& test_case_name); void TrimControlCommand(ControlCommand* origin); protected: - bool is_cybertron_initialized_ = false; + bool is_cyber_initialized_ = false; std::mutex mutex_; - cybertron::TimerComponentConfig component_config_; + cyber::TimerComponentConfig component_config_; - // cybertron readers/writers + // cyber readers/writers std::shared_ptr> chassis_writer_; std::shared_ptr> localization_writer_; std::shared_ptr> planning_writer_; @@ -88,22 +88,22 @@ class ControlComponentTest : public ::testing::Test { PadMessage pad_message_; }; -void ControlComponentTest::SetupCybertron() { - if (is_cybertron_initialized_) { +void ControlComponentTest::SetupCyber() { + if (is_cyber_initialized_) { return; } - // init cybertron framework - apollo::cybertron::Init("control_test"); + // init cyber framework + apollo::cyber::Init("control_test"); - Clock::SetMode(Clock::CYBERTRON); + Clock::SetMode(Clock::CYBER); component_config_.set_name("control_test"); component_config_.set_interval(0.01); - std::shared_ptr node( - apollo::cybertron::CreateNode("control_test")); + std::shared_ptr node( + apollo::cyber::CreateNode("control_test")); chassis_writer_ = node->CreateWriter(FLAGS_chassis_topic); localization_writer_ = @@ -120,7 +120,7 @@ void ControlComponentTest::SetupCybertron() { control_command_.CopyFrom(*control_command); }); - is_cybertron_initialized_ = true; + is_cyber_initialized_ = true; } bool ControlComponentTest::FeedTestData() { diff --git a/modules/control/controller/BUILD b/modules/control/controller/BUILD index f6b361e2550..c072d85ea20 100644 --- a/modules/control/controller/BUILD +++ b/modules/control/controller/BUILD @@ -21,7 +21,7 @@ cc_library( ], deps = [ ":controller_interface", - "//cybertron", + "//cyber", "//modules/common/configs:vehicle_config_helper", "//modules/common/filters:digital_filter", "//modules/common/filters:digital_filter_coefficients", @@ -50,7 +50,7 @@ cc_library( ], deps = [ ":controller_interface", - "//cybertron", + "//cyber", "//modules/common/configs:vehicle_config_helper", "//modules/common/filters:digital_filter", "//modules/common/filters:digital_filter_coefficients", @@ -75,7 +75,7 @@ cc_library( ], deps = [ ":controller_interface", - "//cybertron", + "//cyber", "//modules/common/configs:vehicle_config_helper", "//modules/common/filters:digital_filter", "//modules/common/filters:digital_filter_coefficients", @@ -121,7 +121,7 @@ cc_library( ":lon_controller", ":mpc_controller", "//modules/canbus/proto:canbus_proto", - "//cybertron", + "//cyber", "//modules/common/time", "//modules/common/util:factory", "//modules/control/proto:control_proto", @@ -138,7 +138,7 @@ cc_test( data = ["//modules/control/testdata:control_testdata"], deps = [ ":lon_controller", - "//cybertron", + "//cyber", "//modules/common/time", "//modules/common/util", "//modules/common/vehicle_state:vehicle_state_provider", @@ -158,7 +158,7 @@ cc_test( data = ["//modules/control/testdata:control_testdata"], deps = [ ":lat_controller", - "//cybertron", + "//cyber", "//modules/common/time", "//modules/common/util", "//modules/common/vehicle_state:vehicle_state_provider", @@ -178,7 +178,7 @@ cc_test( data = ["//modules/control/testdata:control_testdata"], deps = [ ":mpc_controller", - "//cybertron", + "//cyber", "//modules/common/time", "//modules/common/util", "//modules/common/vehicle_state:vehicle_state_provider", diff --git a/modules/control/controller/controller_agent.cc b/modules/control/controller/controller_agent.cc index 40f4fe5f9fb..5e6c98b999c 100644 --- a/modules/control/controller/controller_agent.cc +++ b/modules/control/controller/controller_agent.cc @@ -18,7 +18,7 @@ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/time/time.h" #include "modules/control/common/control_gflags.h" #include "modules/control/controller/lat_controller.h" diff --git a/modules/control/controller/lat_controller.cc b/modules/control/controller/lat_controller.cc index e740090c355..c24c02d62be 100644 --- a/modules/control/controller/lat_controller.cc +++ b/modules/control/controller/lat_controller.cc @@ -26,7 +26,7 @@ #include "Eigen/LU" #include "modules/common/configs/vehicle_config_helper.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/math/linear_quadratic_regulator.h" #include "modules/common/math/math_utils.h" #include "modules/common/math/quaternion.h" diff --git a/modules/control/controller/lat_controller_test.cc b/modules/control/controller/lat_controller_test.cc index 202cf85dcaf..c6390a2f11b 100644 --- a/modules/control/controller/lat_controller_test.cc +++ b/modules/control/controller/lat_controller_test.cc @@ -20,7 +20,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "gmock/gmock.h" #include "gtest/gtest.h" #include "modules/common/time/time.h" diff --git a/modules/control/controller/lon_controller.cc b/modules/control/controller/lon_controller.cc index 40a67995b9a..04d90407bfb 100644 --- a/modules/control/controller/lon_controller.cc +++ b/modules/control/controller/lon_controller.cc @@ -19,7 +19,7 @@ #include #include "modules/common/configs/vehicle_config_helper.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/math/math_utils.h" #include "modules/common/time/time.h" #include "modules/common/util/string_util.h" diff --git a/modules/control/controller/lon_controller_test.cc b/modules/control/controller/lon_controller_test.cc index c0ecbbfb273..5c4f6d3f96a 100644 --- a/modules/control/controller/lon_controller_test.cc +++ b/modules/control/controller/lon_controller_test.cc @@ -27,7 +27,7 @@ #include "modules/control/proto/control_conf.pb.h" #include "modules/planning/proto/planning.pb.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/time/time.h" #include "modules/common/util/file.h" #include "modules/common/vehicle_state/vehicle_state_provider.h" diff --git a/modules/control/controller/mpc_controller.cc b/modules/control/controller/mpc_controller.cc index d1c803b470d..a07eb2b9d51 100644 --- a/modules/control/controller/mpc_controller.cc +++ b/modules/control/controller/mpc_controller.cc @@ -26,7 +26,7 @@ #include "Eigen/LU" #include "modules/common/configs/vehicle_config_helper.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/math/math_utils.h" #include "modules/common/math/mpc_solver.h" #include "modules/common/time/time.h" diff --git a/modules/control/controller/mpc_controller_test.cc b/modules/control/controller/mpc_controller_test.cc index 8ce9bc22f72..a6a54ab9c22 100644 --- a/modules/control/controller/mpc_controller_test.cc +++ b/modules/control/controller/mpc_controller_test.cc @@ -20,7 +20,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "gmock/gmock.h" #include "gtest/gtest.h" #include "modules/common/time/time.h" diff --git a/modules/control/integration_tests/BUILD b/modules/control/integration_tests/BUILD index dfa9bc6e86b..e71152c859a 100644 --- a/modules/control/integration_tests/BUILD +++ b/modules/control/integration_tests/BUILD @@ -11,7 +11,7 @@ cc_library( "control_test_base.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/common/proto:geometry_proto", "//modules/common/time", "//modules/control:control_component_lib", diff --git a/modules/control/integration_tests/mpc_controller_test.cc b/modules/control/integration_tests/mpc_controller_test.cc index c6ef6d056eb..03230f1032b 100644 --- a/modules/control/integration_tests/mpc_controller_test.cc +++ b/modules/control/integration_tests/mpc_controller_test.cc @@ -18,7 +18,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "gmock/gmock.h" #include "google/protobuf/text_format.h" #include "gtest/gtest.h" diff --git a/modules/control/integration_tests/relative_position_test.cc b/modules/control/integration_tests/relative_position_test.cc index 8ff25fefa75..59a6f33adc9 100644 --- a/modules/control/integration_tests/relative_position_test.cc +++ b/modules/control/integration_tests/relative_position_test.cc @@ -18,7 +18,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "gmock/gmock.h" #include "google/protobuf/text_format.h" #include "gtest/gtest.h" diff --git a/modules/control/integration_tests/simple_control_test.cc b/modules/control/integration_tests/simple_control_test.cc index a5a77d3e1b5..8fee6d92257 100644 --- a/modules/control/integration_tests/simple_control_test.cc +++ b/modules/control/integration_tests/simple_control_test.cc @@ -18,7 +18,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "gmock/gmock.h" #include "google/protobuf/text_format.h" #include "gtest/gtest.h" diff --git a/modules/control/launch/control.launch b/modules/control/launch/control.launch index 204f3758a17..9cd86d61211 100644 --- a/modules/control/launch/control.launch +++ b/modules/control/launch/control.launch @@ -1,7 +1,7 @@ - + control /apollo/modules/control/dag/control.dag control - + diff --git a/modules/control/tools/BUILD b/modules/control/tools/BUILD index b061b6fc826..eef021ea489 100644 --- a/modules/control/tools/BUILD +++ b/modules/control/tools/BUILD @@ -6,7 +6,7 @@ cc_binary( name = "control_tester", srcs = ["control_tester.cc"], deps = [ - "//cybertron", + "//cyber", "//modules/canbus/proto:canbus_proto", "//modules/common/adapters:adapter_gflags", "//modules/common/util", @@ -22,7 +22,7 @@ cc_binary( srcs = ["pad_terminal.cc"], deps = [ "//external:gflags", - "//cybertron", + "//cyber", "//modules/canbus/proto:canbus_proto", "//modules/common/adapters:adapter_gflags", "//modules/common/util", diff --git a/modules/control/tools/control_tester.cc b/modules/control/tools/control_tester.cc index 087791c2aab..0f9a21113e0 100644 --- a/modules/control/tools/control_tester.cc +++ b/modules/control/tools/control_tester.cc @@ -19,13 +19,13 @@ #include "gflags/gflags.h" -#include "cybertron/cybertron.h" -#include "cybertron/time/rate.h" -#include "cybertron/time/time.h" +#include "cyber/cyber.h" +#include "cyber/time/rate.h" +#include "cyber/time/time.h" #include "modules/canbus/proto/chassis.pb.h" #include "modules/common/adapters/adapter_gflags.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/file.h" #include "modules/control/common/control_gflags.h" #include "modules/control/proto/pad_msg.pb.h" @@ -54,13 +54,13 @@ DEFINE_int32(feed_frequency, 10, int main(int argc, char** argv) { using apollo::canbus::Chassis; using apollo::control::PadMessage; - using apollo::cybertron::Time; + using apollo::cyber::Time; using apollo::localization::LocalizationEstimate; using apollo::planning::ADCTrajectory; using std::this_thread::sleep_for; google::ParseCommandLineFlags(&argc, &argv, true); - apollo::cybertron::Init(argv[0]); + apollo::cyber::Init(argv[0]); FLAGS_alsologtostderr = true; Chassis chassis; @@ -91,8 +91,8 @@ int main(int argc, char** argv) { return -1; } - std::shared_ptr node( - apollo::cybertron::CreateNode("control_tester")); + std::shared_ptr node( + apollo::cyber::CreateNode("control_tester")); auto chassis_writer = node->CreateWriter(FLAGS_chassis_topic); auto localization_writer = node->CreateWriter(FLAGS_localization_topic); diff --git a/modules/control/tools/pad_terminal.cc b/modules/control/tools/pad_terminal.cc index bdaea07b63a..a5069a44eee 100644 --- a/modules/control/tools/pad_terminal.cc +++ b/modules/control/tools/pad_terminal.cc @@ -17,10 +17,10 @@ #include #include -#include "cybertron/common/log.h" -#include "cybertron/common/macros.h" -#include "cybertron/cybertron.h" -#include "cybertron/time/time.h" +#include "cyber/common/log.h" +#include "cyber/common/macros.h" +#include "cyber/cyber.h" +#include "cyber/time/time.h" #include "modules/canbus/proto/chassis.pb.h" #include "modules/control/proto/pad_msg.pb.h" @@ -37,10 +37,10 @@ using apollo::common::time::AsInt64; using apollo::common::time::Clock; using apollo::control::DrivingAction; using apollo::control::PadMessage; -using apollo::cybertron::CreateNode; -using apollo::cybertron::Node; -using apollo::cybertron::Reader; -using apollo::cybertron::Writer; +using apollo::cyber::CreateNode; +using apollo::cyber::Node; +using apollo::cyber::Reader; +using apollo::cyber::Writer; class PadTerminal { public: @@ -148,14 +148,14 @@ class PadTerminal { } // namespace int main(int argc, char **argv) { - apollo::cybertron::Init("pad_terminal"); + apollo::cyber::Init("pad_terminal"); FLAGS_alsologtostderr = true; FLAGS_v = 3; google::ParseCommandLineFlags(&argc, &argv, true); PadTerminal pad_terminal; pad_terminal.init(); pad_terminal.help(); - apollo::cybertron::WaitForShutdown(); + apollo::cyber::WaitForShutdown(); pad_terminal.stop(); return 0; } diff --git a/modules/data/BUILD b/modules/data/BUILD index ad41f9ae66f..e93b8cef8fb 100644 --- a/modules/data/BUILD +++ b/modules/data/BUILD @@ -10,7 +10,7 @@ cc_library( "//modules/data/proto:data_proto", "//modules/data/common:data_gflags", "//modules/data/proto:data_conf_proto", - "//cybertron", + "//cyber", "//modules/data/recorder:record_service", ] ) diff --git a/modules/data/data_component.cc b/modules/data/data_component.cc index b17b2bb7895..67ab3e43cfc 100644 --- a/modules/data/data_component.cc +++ b/modules/data/data_component.cc @@ -15,7 +15,7 @@ *****************************************************************************/ #include "modules/data/data_component.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/adapters/adapter_gflags.h" #include "modules/common/util/message_util.h" diff --git a/modules/data/data_component.h b/modules/data/data_component.h index dcaf5f395af..4ebf6dfe4e3 100644 --- a/modules/data/data_component.h +++ b/modules/data/data_component.h @@ -23,9 +23,9 @@ #include #include -#include "cybertron/common/macros.h" -#include "cybertron/component/timer_component.h" -#include "cybertron/cybertron.h" +#include "cyber/common/macros.h" +#include "cyber/component/timer_component.h" +#include "cyber/cyber.h" #include "modules/data/proto/data.pb.h" #include "modules/data/proto/data_conf.pb.h" @@ -38,7 +38,7 @@ namespace apollo { namespace data { class DataComponent final - : public apollo::cybertron::Component { + : public apollo::cyber::Component { public: DataComponent() = default; ~DataComponent() = default; @@ -54,11 +54,11 @@ class DataComponent final const std::shared_ptr &data_input_cmd); private: DataConf data_conf_; - std::shared_ptr> + std::shared_ptr> data_input_cmd_reader_; }; -CYBERTRON_REGISTER_COMPONENT(DataComponent) +CYBER_REGISTER_COMPONENT(DataComponent) } // namespace data } // namespace apollo diff --git a/modules/data/data_component_test.cc b/modules/data/data_component_test.cc index ab3bdc2f71c..644a7511ab6 100644 --- a/modules/data/data_component_test.cc +++ b/modules/data/data_component_test.cc @@ -18,7 +18,7 @@ #include "gflags/gflags.h" #include "gtest/gtest.h" -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/data/proto/data.pb.h" #include "modules/data/proto/data_conf.pb.h" @@ -33,43 +33,43 @@ namespace apollo { namespace data { using apollo::common::time::Clock; -using apollo::cybertron::ComponentConfig; -using apollo::cybertron::Reader; -using apollo::cybertron::Writer; +using apollo::cyber::ComponentConfig; +using apollo::cyber::Reader; +using apollo::cyber::Writer; class DataComponentTest : public ::testing::Test { public: virtual void SetUp() { - SetupCybertron(); + SetupCyber(); } protected: - void SetupCybertron(); + void SetupCyber(); bool RunDataTest(); protected: - bool is_cybertron_initialized_ = false; - cybertron::ComponentConfig component_config_; + bool is_cyber_initialized_ = false; + cyber::ComponentConfig component_config_; std::shared_ptr> data_writer_; std::shared_ptr data_component_; }; -void DataComponentTest::SetupCybertron() { - if (is_cybertron_initialized_) { +void DataComponentTest::SetupCyber() { + if (is_cyber_initialized_) { return; } - apollo::cybertron::Init("data_test"); - Clock::SetMode(Clock::CYBERTRON); + apollo::cyber::Init("data_test"); + Clock::SetMode(Clock::CYBER); component_config_.set_name("data_test"); component_config_.add_readers(); - std::shared_ptr node( - apollo::cybertron::CreateNode("data_test")); + std::shared_ptr node( + apollo::cyber::CreateNode("data_test")); data_writer_ = node->CreateWriter(FLAGS_data_topic); - is_cybertron_initialized_ = true; + is_cyber_initialized_ = true; } bool DataComponentTest::RunDataTest() { diff --git a/modules/data/launch/data.launch b/modules/data/launch/data.launch index ff2a71e970c..5b22517be67 100644 --- a/modules/data/launch/data.launch +++ b/modules/data/launch/data.launch @@ -1,7 +1,7 @@ - + data /apollo/modules/data/dag/data.dag data - + diff --git a/modules/data/recorder/BUILD b/modules/data/recorder/BUILD index e84201d988b..9a04d26de50 100644 --- a/modules/data/recorder/BUILD +++ b/modules/data/recorder/BUILD @@ -7,7 +7,7 @@ cc_library( srcs = ["record_service.cc"], hdrs = ["record_service.h"], deps = [ - "//cybertron", + "//cyber", "//modules/common/adapters:adapter_gflags", "//modules/common/util", "//modules/data/common:data_gflags", diff --git a/modules/data/recorder/record_service.cc b/modules/data/recorder/record_service.cc index 5fdf303c562..ede27b36df2 100644 --- a/modules/data/recorder/record_service.cc +++ b/modules/data/recorder/record_service.cc @@ -18,7 +18,7 @@ #include "modules/data/recorder/record_service.h" #include "gflags/gflags.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace data { @@ -26,7 +26,7 @@ namespace data { RecordService::RecordService() = default; bool RecordService::Init( - const std::shared_ptr& node) { + const std::shared_ptr& node) { AINFO << "RecordService::Init(), starting..."; Instance()->server_ = node->CreateService( diff --git a/modules/data/recorder/record_service.h b/modules/data/recorder/record_service.h index baa18520d54..d010cb42097 100644 --- a/modules/data/recorder/record_service.h +++ b/modules/data/recorder/record_service.h @@ -18,9 +18,9 @@ #include -#include "cybertron/common/macros.h" -#include "cybertron/cybertron.h" -#include "cybertron/service/service.h" +#include "cyber/common/macros.h" +#include "cyber/cyber.h" +#include "cyber/service/service.h" #include "modules/data/proto/record_request.pb.h" #include "modules/data/proto/record_response.pb.h" @@ -33,13 +33,13 @@ namespace data { class RecordService { public: - static bool Init(const std::shared_ptr& node); + static bool Init(const std::shared_ptr& node); private: static void OnRecordRequest( const std::shared_ptr &request, const std::shared_ptr &response); private: - std::shared_ptr> + std::shared_ptr> server_; DECLARE_SINGLETON(RecordService); }; diff --git a/modules/data/util/info_collector.cc b/modules/data/util/info_collector.cc index cc23e1d955a..a6de31847b4 100644 --- a/modules/data/util/info_collector.cc +++ b/modules/data/util/info_collector.cc @@ -73,7 +73,7 @@ InfoCollector::InfoCollector() { } } -void InfoCollector::Init(const std::shared_ptr& node) { +void InfoCollector::Init(const std::shared_ptr& node) { Instance()->routing_request_reader_ = node->CreateReader( FLAGS_routing_request_topic); diff --git a/modules/data/util/info_collector.h b/modules/data/util/info_collector.h index e6ca3d0c346..73c80a1dcbb 100644 --- a/modules/data/util/info_collector.h +++ b/modules/data/util/info_collector.h @@ -19,8 +19,8 @@ #include #include -#include "cybertron/common/macros.h" -#include "cybertron/cybertron.h" +#include "cyber/common/macros.h" +#include "cyber/cyber.h" #include "modules/data/proto/static_info.pb.h" /** @@ -32,7 +32,7 @@ namespace data { class InfoCollector { public: - static void Init(const std::shared_ptr& node); + static void Init(const std::shared_ptr& node); // Get task information. static const StaticInfo &GetStaticInfo(); @@ -50,7 +50,7 @@ class InfoCollector { private: StaticInfo static_info_; StaticInfoConf config_; - std::shared_ptr> + std::shared_ptr> routing_request_reader_; DECLARE_SINGLETON(InfoCollector); diff --git a/modules/dreamview/backend/dreamview.cc b/modules/dreamview/backend/dreamview.cc index e3338619097..ce445b74465 100644 --- a/modules/dreamview/backend/dreamview.cc +++ b/modules/dreamview/backend/dreamview.cc @@ -36,7 +36,7 @@ Dreamview::~Dreamview() { Stop(); } void Dreamview::TerminateProfilingMode() { Stop(); - apollo::cybertron::Shutdown(); + apollo::cyber::Shutdown(); AWARN << "Profiling timer called shutdown!"; } @@ -45,7 +45,7 @@ Status Dreamview::Init() { if (FLAGS_dreamview_profiling_mode && FLAGS_dreamview_profiling_duration > 0.0) { - exit_timer_.reset(new cybertron::Timer( + exit_timer_.reset(new cyber::Timer( FLAGS_dreamview_profiling_duration, [this]() { this->TerminateProfilingMode(); }, false)); diff --git a/modules/dreamview/backend/dreamview.h b/modules/dreamview/backend/dreamview.h index 8965ed3123e..8611a7639df 100644 --- a/modules/dreamview/backend/dreamview.h +++ b/modules/dreamview/backend/dreamview.h @@ -20,7 +20,7 @@ #include #include "CivetServer.h" -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/common/status/status.h" #include "modules/dreamview/backend/handlers/image_handler.h" #include "modules/dreamview/backend/handlers/websocket_handler.h" @@ -48,7 +48,7 @@ class Dreamview { private: void TerminateProfilingMode(); - std::unique_ptr exit_timer_; + std::unique_ptr exit_timer_; std::unique_ptr sim_world_updater_; std::unique_ptr point_cloud_updater_; diff --git a/modules/dreamview/backend/handlers/BUILD b/modules/dreamview/backend/handlers/BUILD index 3f601feb410..756d007dcc5 100644 --- a/modules/dreamview/backend/handlers/BUILD +++ b/modules/dreamview/backend/handlers/BUILD @@ -29,7 +29,7 @@ cc_library( "image_handler.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/common/adapters:adapter_gflags", "//modules/common/configs:config_gflags", "//modules/drivers/proto:sensor_proto", @@ -46,7 +46,7 @@ cc_test( ], deps = [ ":websocket_handler", - "//cybertron", + "//cyber", "@gtest//:main", ], ) diff --git a/modules/dreamview/backend/handlers/image_handler.cc b/modules/dreamview/backend/handlers/image_handler.cc index ab1e0620804..481fa110bdc 100644 --- a/modules/dreamview/backend/handlers/image_handler.cc +++ b/modules/dreamview/backend/handlers/image_handler.cc @@ -17,7 +17,7 @@ limitations under the License. #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/adapters/adapter_gflags.h" #include "modules/common/configs/config_gflags.h" @@ -61,7 +61,7 @@ void ImageHandler::OnImageShort(const std::shared_ptr &image) { } ImageHandler::ImageHandler() - : requests_(0), node_(cybertron::CreateNode("image_handler")) { + : requests_(0), node_(cyber::CreateNode("image_handler")) { node_->CreateReader( FLAGS_image_front_topic, [this](const std::shared_ptr &image) { diff --git a/modules/dreamview/backend/handlers/image_handler.h b/modules/dreamview/backend/handlers/image_handler.h index d359c0adba2..16988f21c6c 100644 --- a/modules/dreamview/backend/handlers/image_handler.h +++ b/modules/dreamview/backend/handlers/image_handler.h @@ -27,7 +27,7 @@ #include #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/drivers/proto/sensor_image.pb.h" #include "CivetServer.h" @@ -67,7 +67,7 @@ class ImageHandler : public CivetHandler { std::mutex mutex_; std::condition_variable cvar_; - std::unique_ptr node_; + std::unique_ptr node_; }; } // namespace dreamview diff --git a/modules/dreamview/backend/handlers/websocket_handler.cc b/modules/dreamview/backend/handlers/websocket_handler.cc index 642167cd81f..f3f2121f0a7 100644 --- a/modules/dreamview/backend/handlers/websocket_handler.cc +++ b/modules/dreamview/backend/handlers/websocket_handler.cc @@ -19,7 +19,7 @@ limitations under the License. #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/time/time.h" #include "modules/common/util/map_util.h" #include "modules/common/util/string_util.h" diff --git a/modules/dreamview/backend/handlers/websocket_handler_test.cc b/modules/dreamview/backend/handlers/websocket_handler_test.cc index 53577dc5679..3033d4c7b7f 100644 --- a/modules/dreamview/backend/handlers/websocket_handler_test.cc +++ b/modules/dreamview/backend/handlers/websocket_handler_test.cc @@ -19,7 +19,7 @@ limitations under the License. #include #include "gmock/gmock.h" #include "gtest/gtest.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" using ::testing::ElementsAre; diff --git a/modules/dreamview/backend/hmi/BUILD b/modules/dreamview/backend/hmi/BUILD index 0c0687d6a67..4ab55ac92a2 100644 --- a/modules/dreamview/backend/hmi/BUILD +++ b/modules/dreamview/backend/hmi/BUILD @@ -7,7 +7,7 @@ cc_library( srcs = ["vehicle_manager.cc"], hdrs = ["vehicle_manager.h"], deps = [ - "//cybertron", + "//cyber", "//modules/common/util", "//modules/common/util:string_util", "//modules/dreamview/proto:hmi_config_proto", @@ -61,7 +61,7 @@ cc_library( ], deps = [ ":vehicle_manager", - "//cybertron", + "//cyber", "//modules/common/adapters:adapter_gflags", "//modules/common/configs:config_gflags", "//modules/common/kv_db", diff --git a/modules/dreamview/backend/hmi/hmi.cc b/modules/dreamview/backend/hmi/hmi.cc index 3dc5a40fbf1..c9015960566 100644 --- a/modules/dreamview/backend/hmi/hmi.cc +++ b/modules/dreamview/backend/hmi/hmi.cc @@ -41,7 +41,7 @@ using RLock = boost::shared_lock; constexpr int HMI::kMinBroadcastIntervalMs; HMI::HMI(WebSocketHandler *websocket, MapService *map_service) - : node_(cybertron::CreateNode("hmi")), + : node_(cyber::CreateNode("hmi")), websocket_(websocket), map_service_(map_service), monitor_log_buffer_(apollo::common::monitor::MonitorMessageItem::HMI) { @@ -50,7 +50,7 @@ HMI::HMI(WebSocketHandler *websocket, MapService *map_service) // Register websocket message handlers. if (websocket_) { RegisterMessageHandlers(); - cybertron::Async(&HMI::BroadcastStatusThreadLoop, this); + cyber::Async(&HMI::BroadcastStatusThreadLoop, this); } audio_capture_writer_ = diff --git a/modules/dreamview/backend/hmi/hmi.h b/modules/dreamview/backend/hmi/hmi.h index db0cbb5563a..041cbfe2a53 100644 --- a/modules/dreamview/backend/hmi/hmi.h +++ b/modules/dreamview/backend/hmi/hmi.h @@ -48,8 +48,8 @@ class HMI { void RegisterMessageHandlers(); - std::shared_ptr node_; - std::shared_ptr> audio_capture_writer_; + std::shared_ptr node_; + std::shared_ptr> audio_capture_writer_; std::unique_ptr hmi_worker_; diff --git a/modules/dreamview/backend/hmi/hmi_worker.cc b/modules/dreamview/backend/hmi/hmi_worker.cc index 665b121de4d..98a4f6986fd 100644 --- a/modules/dreamview/backend/hmi/hmi_worker.cc +++ b/modules/dreamview/backend/hmi/hmi_worker.cc @@ -128,7 +128,7 @@ void SetGlobalFlag(const std::string &flag_name, const ValueType &value, } // namespace -HMIWorker::HMIWorker(const std::shared_ptr &node) { +HMIWorker::HMIWorker(const std::shared_ptr &node) { // Init HMIConfig. CHECK(common::util::GetProtoFromFile(FLAGS_hmi_config_filename, &config_)) << "Unable to parse HMI config file " << FLAGS_hmi_config_filename; @@ -242,7 +242,7 @@ bool HMIWorker::CyberLaunch(const std::string& command) const { } void HMIWorker::InitReadersAndWriters( - const std::shared_ptr &node) { + const std::shared_ptr &node) { // Received Chassis, trigger action if there is high beam signal. chassis_reader_ = node->CreateReader( FLAGS_chassis_topic, [this](const std::shared_ptr &chassis) { @@ -379,7 +379,7 @@ void HMIWorker::ChangeToMap(const std::string &map_name) { apollo::common::KVDB::Put("apollo:dreamview:map", map_name); SetGlobalFlag("map_dir", *map_dir, &FLAGS_map_dir); - cybertron::Async(&HMIWorker::RunModeCommand, this, "stop"); + cyber::Async(&HMIWorker::RunModeCommand, this, "stop"); // Trigger registered change map handlers. for (const auto handler : change_map_handlers_) { diff --git a/modules/dreamview/backend/hmi/hmi_worker.h b/modules/dreamview/backend/hmi/hmi_worker.h index 9b6b220f4fd..19667aedeaa 100644 --- a/modules/dreamview/backend/hmi/hmi_worker.h +++ b/modules/dreamview/backend/hmi/hmi_worker.h @@ -23,7 +23,7 @@ #include "boost/thread/locks.hpp" #include "boost/thread/shared_mutex.hpp" -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/canbus/proto/chassis.pb.h" #include "modules/common/proto/drive_event.pb.h" @@ -47,7 +47,7 @@ using ChangeVehicleHandler = std::function; // Singleton worker which does the actual work of HMI actions. class HMIWorker { public: - explicit HMIWorker(const std::shared_ptr& node); + explicit HMIWorker(const std::shared_ptr& node); // High level HMI action trigger. bool Trigger(const HMIAction action); @@ -127,7 +127,7 @@ class HMIWorker { private: void InitReadersAndWriters( - const std::shared_ptr& node); + const std::shared_ptr& node); // Run command: scripts/cyber_launch.sh bool CyberLaunch(const std::string& command) const; @@ -141,9 +141,9 @@ class HMIWorker { std::vector change_map_handlers_; std::vector change_vehicle_handlers_; - std::shared_ptr> chassis_reader_; - std::shared_ptr> pad_writer_; - std::shared_ptr> + std::shared_ptr> chassis_reader_; + std::shared_ptr> pad_writer_; + std::shared_ptr> drive_event_writer_; }; diff --git a/modules/dreamview/backend/hmi/hmi_worker_test.cc b/modules/dreamview/backend/hmi/hmi_worker_test.cc index ea09b975c40..f9220d5e60c 100644 --- a/modules/dreamview/backend/hmi/hmi_worker_test.cc +++ b/modules/dreamview/backend/hmi/hmi_worker_test.cc @@ -18,7 +18,7 @@ #include "google/protobuf/util/message_differencer.h" #include "gtest/gtest.h" -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/common/util/file.h" DECLARE_string(modes_config_path); @@ -27,9 +27,9 @@ namespace apollo { namespace dreamview { TEST(HMIWorkerTest, Init) { - apollo::cybertron::Init(); - std::shared_ptr node( - apollo::cybertron::CreateNode("hmi_worker_tester")); + apollo::cyber::Init(); + std::shared_ptr node( + apollo::cyber::CreateNode("hmi_worker_tester")); HMIWorker worker(node); const auto& hmi_config = worker.GetConfig(); EXPECT_GT(hmi_config.available_vehicles().size(), 0); diff --git a/modules/dreamview/backend/hmi/vehicle_manager.h b/modules/dreamview/backend/hmi/vehicle_manager.h index 2d57667ec4b..babcd206bf6 100644 --- a/modules/dreamview/backend/hmi/vehicle_manager.h +++ b/modules/dreamview/backend/hmi/vehicle_manager.h @@ -18,7 +18,7 @@ #include -#include "cybertron/common/macros.h" +#include "cyber/common/macros.h" #include "modules/dreamview/proto/hmi_config.pb.h" diff --git a/modules/dreamview/backend/hmi/vehicle_manager_main.cc b/modules/dreamview/backend/hmi/vehicle_manager_main.cc index 50803470cb6..4443945cd7a 100644 --- a/modules/dreamview/backend/hmi/vehicle_manager_main.cc +++ b/modules/dreamview/backend/hmi/vehicle_manager_main.cc @@ -17,7 +17,7 @@ #include "modules/dreamview/backend/hmi/vehicle_manager.h" #include "gflags/gflags.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" DEFINE_string(vehicle_data_path, "modules/calibration/data/mkz_example", "Vehicle data path."); diff --git a/modules/dreamview/backend/main.cc b/modules/dreamview/backend/main.cc index 49910bc9f28..da5ce74d3db 100644 --- a/modules/dreamview/backend/main.cc +++ b/modules/dreamview/backend/main.cc @@ -14,12 +14,12 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/init.h" +#include "cyber/init.h" #include "modules/dreamview/backend/dreamview.h" int main(int argc, char *argv[]) { google::ParseCommandLineFlags(&argc, &argv, true); - apollo::cybertron::Init(argv[0]); + apollo::cyber::Init(argv[0]); apollo::dreamview::Dreamview dreamview; const bool init_success = dreamview.Init().ok() && dreamview.Start().ok(); @@ -28,6 +28,6 @@ int main(int argc, char *argv[]) { return -1; } - apollo::cybertron::WaitForShutdown(); + apollo::cyber::WaitForShutdown(); return 0; } diff --git a/modules/dreamview/backend/point_cloud/BUILD b/modules/dreamview/backend/point_cloud/BUILD index a424e39efea..8b22583e6b9 100644 --- a/modules/dreamview/backend/point_cloud/BUILD +++ b/modules/dreamview/backend/point_cloud/BUILD @@ -14,7 +14,7 @@ cc_library( "-lboost_thread", ], deps = [ - "//cybertron", + "//cyber", "//modules/common/adapters:adapter_gflags", "//modules/dreamview/backend/common:dreamview_gflags", "//modules/dreamview/backend/handlers:websocket_handler", diff --git a/modules/dreamview/backend/point_cloud/point_cloud_updater.cc b/modules/dreamview/backend/point_cloud/point_cloud_updater.cc index d5c3c656f22..fc85acec333 100644 --- a/modules/dreamview/backend/point_cloud/point_cloud_updater.cc +++ b/modules/dreamview/backend/point_cloud/point_cloud_updater.cc @@ -18,7 +18,7 @@ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/adapters/adapter_gflags.h" #include "modules/common/time/time.h" #include "modules/common/util/file.h" @@ -40,7 +40,7 @@ float PointCloudUpdater::lidar_height_ = kDefaultLidarHeight; boost::shared_mutex PointCloudUpdater::mutex_; PointCloudUpdater::PointCloudUpdater(WebSocketHandler *websocket) - : node_(cybertron::CreateNode("point_cloud")), + : node_(cyber::CreateNode("point_cloud")), websocket_(websocket), point_cloud_str_(""), future_ready_(true) { @@ -170,7 +170,7 @@ void PointCloudUpdater::UpdatePointCloud( pcl_ptr->points[i].z = point_cloud->point(i).z(); } std::future f = - cybertron::Async(&PointCloudUpdater::FilterPointCloud, + cyber::Async(&PointCloudUpdater::FilterPointCloud, this, pcl_ptr); async_future_ = std::move(f); } diff --git a/modules/dreamview/backend/point_cloud/point_cloud_updater.h b/modules/dreamview/backend/point_cloud/point_cloud_updater.h index b1b4e8406bf..24d67f697a6 100644 --- a/modules/dreamview/backend/point_cloud/point_cloud_updater.h +++ b/modules/dreamview/backend/point_cloud/point_cloud_updater.h @@ -28,8 +28,8 @@ #include "boost/thread/locks.hpp" #include "boost/thread/shared_mutex.hpp" -#include "cybertron/common/log.h" -#include "cybertron/cybertron.h" +#include "cyber/common/log.h" +#include "cyber/cyber.h" #include "modules/common/util/string_util.h" #include "modules/dreamview/backend/handlers/websocket_handler.h" #include "modules/drivers/proto/pointcloud.pb.h" @@ -88,7 +88,7 @@ class PointCloudUpdater { constexpr static float kDefaultLidarHeight = 1.91; - std::unique_ptr node_; + std::unique_ptr node_; WebSocketHandler *websocket_; @@ -100,10 +100,10 @@ class PointCloudUpdater { std::future async_future_; std::atomic future_ready_; - // Cybertron messsage readers. - std::shared_ptr> + // Cyber messsage readers. + std::shared_ptr> localization_reader_; - std::shared_ptr> + std::shared_ptr> point_cloud_reader_; double last_point_cloud_time_ = 0.0; diff --git a/modules/dreamview/backend/sim_control/BUILD b/modules/dreamview/backend/sim_control/BUILD index fd73e973b9e..e761c294adb 100644 --- a/modules/dreamview/backend/sim_control/BUILD +++ b/modules/dreamview/backend/sim_control/BUILD @@ -12,7 +12,7 @@ cc_library( "sim_control_interface.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/common/adapters:adapter_gflags", "//modules/dreamview/backend/common:dreamview_gflags", "//modules/dreamview/backend/map:map_service", diff --git a/modules/dreamview/backend/sim_control/sim_control.cc b/modules/dreamview/backend/sim_control/sim_control.cc index 1f0fb80a75a..f74abf2bcf5 100644 --- a/modules/dreamview/backend/sim_control/sim_control.cc +++ b/modules/dreamview/backend/sim_control/sim_control.cc @@ -69,7 +69,7 @@ bool IsSameHeader(const Header& lhs, const Header& rhs) { SimControl::SimControl(const MapService* map_service) : map_service_(map_service), - node_(cybertron::CreateNode("sim_control")), + node_(cyber::CreateNode("sim_control")), current_trajectory_(std::make_shared()) { InitTimerAndIO(); } @@ -105,9 +105,9 @@ void SimControl::InitTimerAndIO() { node_->CreateWriter(FLAGS_prediction_topic); // Start timer to publish localization and chassis messages. - sim_control_timer_.reset(new cybertron::Timer( + sim_control_timer_.reset(new cyber::Timer( kSimControlIntervalMs, [this]() { this->RunOnce(); }, false)); - sim_prediction_timer_.reset(new cybertron::Timer( + sim_prediction_timer_.reset(new cyber::Timer( kSimPredictionIntervalMs, [this]() { this->PublishDummyPrediction(); }, false)); } diff --git a/modules/dreamview/backend/sim_control/sim_control.h b/modules/dreamview/backend/sim_control/sim_control.h index 65ffa4c7783..2a637ed9c63 100644 --- a/modules/dreamview/backend/sim_control/sim_control.h +++ b/modules/dreamview/backend/sim_control/sim_control.h @@ -23,7 +23,7 @@ #include #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "gtest/gtest_prod.h" @@ -123,30 +123,30 @@ class SimControl : SimControlInterface { const MapService *map_service_ = nullptr; - std::unique_ptr node_; + std::unique_ptr node_; - std::shared_ptr> + std::shared_ptr> localization_reader_; - std::shared_ptr> + std::shared_ptr> planning_reader_; - std::shared_ptr> + std::shared_ptr> routing_response_reader_; - std::shared_ptr> + std::shared_ptr> navigation_reader_; - std::shared_ptr> + std::shared_ptr> prediction_reader_; - std::shared_ptr> + std::shared_ptr> localization_writer_; - std::shared_ptr> chassis_writer_; - std::shared_ptr> + std::shared_ptr> chassis_writer_; + std::shared_ptr> prediction_writer_; // The timer to publish simulated localization and chassis messages. - std::unique_ptr sim_control_timer_; + std::unique_ptr sim_control_timer_; // The timer to publish dummy prediction - std::unique_ptr sim_prediction_timer_; + std::unique_ptr sim_prediction_timer_; // Time interval of the timer, in milliseconds. static constexpr double kSimControlIntervalMs = 10; diff --git a/modules/dreamview/backend/sim_control/sim_control_test.cc b/modules/dreamview/backend/sim_control/sim_control_test.cc index 5a324feaa90..6d701c930c9 100644 --- a/modules/dreamview/backend/sim_control/sim_control_test.cc +++ b/modules/dreamview/backend/sim_control/sim_control_test.cc @@ -18,7 +18,7 @@ #include -#include "cybertron/blocker/blocker_manager.h" +#include "cyber/blocker/blocker_manager.h" #include "gmock/gmock.h" #include "gtest/gtest.h" @@ -31,7 +31,7 @@ using apollo::canbus::Chassis; using apollo::common::math::HeadingToQuaternion; using apollo::common::time::Clock; -using apollo::cybertron::blocker::BlockerManager; +using apollo::cyber::blocker::BlockerManager; using apollo::localization::LocalizationEstimate; using apollo::planning::ADCTrajectory; using apollo::prediction::PredictionObstacles; @@ -43,7 +43,7 @@ namespace dreamview { class SimControlTest : public ::testing::Test { public: static void SetUpTestCase() { - cybertron::GlobalData::Instance()->EnableSimulationMode(); + cyber::GlobalData::Instance()->EnableSimulationMode(); } virtual void SetUp() { diff --git a/modules/dreamview/backend/simulation_world/BUILD b/modules/dreamview/backend/simulation_world/BUILD index 9edd8c5084e..338833ff27b 100644 --- a/modules/dreamview/backend/simulation_world/BUILD +++ b/modules/dreamview/backend/simulation_world/BUILD @@ -12,7 +12,7 @@ cc_library( ], copts = ['-DMODULE_NAME=\\"dreamview\\"'], deps = [ - "//cybertron", + "//cyber", "//modules/canbus/proto:canbus_proto", "//modules/common/adapters:adapter_gflags", "//modules/common/configs:vehicle_config_helper", diff --git a/modules/dreamview/backend/simulation_world/simulation_world_service.cc b/modules/dreamview/backend/simulation_world/simulation_world_service.cc index b24545a8259..47507cb0639 100644 --- a/modules/dreamview/backend/simulation_world/simulation_world_service.cc +++ b/modules/dreamview/backend/simulation_world/simulation_world_service.cc @@ -225,7 +225,7 @@ constexpr int SimulationWorldService::kMaxMonitorItems; SimulationWorldService::SimulationWorldService(const MapService *map_service, bool routing_from_file) - : node_(cybertron::CreateNode("simulation_world")), + : node_(cyber::CreateNode("simulation_world")), map_service_(map_service), monitor_logger_buffer_(MonitorMessageItem::SIMULATOR), ready_to_push_(false) { @@ -286,17 +286,17 @@ void SimulationWorldService::InitWriters() { node_->CreateWriter(FLAGS_navigation_topic); { // configure QoS for routing request writer - apollo::cybertron::proto::RoleAttributes routing_request_attr; + apollo::cyber::proto::RoleAttributes routing_request_attr; routing_request_attr.set_channel_name(FLAGS_routing_request_topic); auto qos = routing_request_attr.mutable_qos_profile(); // only keeps the last message in history qos->set_history( - apollo::cybertron::proto::QosHistoryPolicy::HISTORY_KEEP_LAST); + apollo::cyber::proto::QosHistoryPolicy::HISTORY_KEEP_LAST); // reliable transfer qos->set_reliability( - apollo::cybertron::proto::QosReliabilityPolicy::RELIABILITY_RELIABLE); + apollo::cyber::proto::QosReliabilityPolicy::RELIABILITY_RELIABLE); // when writer find new readers, send all its history messsage - qos->set_durability(apollo::cybertron::proto::QosDurabilityPolicy:: + qos->set_durability(apollo::cyber::proto::QosDurabilityPolicy:: DURABILITY_TRANSIENT_LOCAL); routing_request_writer_ = node_->CreateWriter(routing_request_attr); diff --git a/modules/dreamview/backend/simulation_world/simulation_world_service.h b/modules/dreamview/backend/simulation_world/simulation_world_service.h index e5b2f5e7c6f..d4dfa50f11f 100644 --- a/modules/dreamview/backend/simulation_world/simulation_world_service.h +++ b/modules/dreamview/backend/simulation_world/simulation_world_service.h @@ -29,7 +29,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "gtest/gtest_prod.h" @@ -219,7 +219,7 @@ class SimulationWorldService { * SimulationWorld object when triggered by refresh timer. */ template - void UpdateWithLatestObserved(cybertron::Reader *reader, + void UpdateWithLatestObserved(cyber::Reader *reader, bool logging = true) { if (reader->Empty()) { if (logging) { @@ -238,7 +238,7 @@ class SimulationWorldService { * file. */ template - void DumpMessageFromReader(cybertron::Reader *reader) { + void DumpMessageFromReader(cyber::Reader *reader) { if (reader->Empty()) { AWARN << "Has not received any data from " << reader->GetChannelName() << ". Cannot dump message!"; @@ -252,7 +252,7 @@ class SimulationWorldService { template void UpdateLatency(const std::string &module_name, - cybertron::Reader *reader) { + cyber::Reader *reader) { if (reader->Empty()) { return; } @@ -260,7 +260,7 @@ class SimulationWorldService { const auto header = reader->GetLatestObserved()->header(); const double publish_time_sec = header.timestamp_sec(); const double sensor_time_sec = - apollo::cybertron::Time( + apollo::cyber::Time( std::max({header.lidar_timestamp(), header.camera_timestamp(), header.radar_timestamp()})) .ToSecond(); @@ -309,7 +309,7 @@ class SimulationWorldService { point->set_v(points[points.size() - 1].v()); } - std::unique_ptr node_; + std::unique_ptr node_; // The underlying SimulationWorld object, owned by the // SimulationWorldService instance. @@ -342,39 +342,39 @@ class SimulationWorldService { std::atomic ready_to_push_; // Readers. - std::shared_ptr> chassis_reader_; - std::shared_ptr> gps_reader_; - std::shared_ptr> + std::shared_ptr> chassis_reader_; + std::shared_ptr> gps_reader_; + std::shared_ptr> localization_reader_; - std::shared_ptr> + std::shared_ptr> perception_obstacle_reader_; - std::shared_ptr> + std::shared_ptr> perception_traffic_light_reader_; - std::shared_ptr> + std::shared_ptr> prediction_obstacle_reader_; - std::shared_ptr> + std::shared_ptr> planning_reader_; - std::shared_ptr> + std::shared_ptr> control_command_reader_; - std::shared_ptr> + std::shared_ptr> navigation_reader_; - std::shared_ptr> + std::shared_ptr> relative_map_reader_; - std::shared_ptr> + std::shared_ptr> drive_event_reader_; - std::shared_ptr> + std::shared_ptr> monitor_reader_; - std::shared_ptr> + std::shared_ptr> routing_request_reader_; - std::shared_ptr> + std::shared_ptr> routing_response_reader_; // Writers. - std::shared_ptr> + std::shared_ptr> navigation_writer_; - std::shared_ptr> + std::shared_ptr> routing_request_writer_; - std::shared_ptr> + std::shared_ptr> routing_response_writer_; FRIEND_TEST(SimulationWorldServiceTest, UpdateMonitorSuccess); diff --git a/modules/dreamview/backend/simulation_world/simulation_world_service_test.cc b/modules/dreamview/backend/simulation_world/simulation_world_service_test.cc index 217ae500e57..c6078d2d0a4 100644 --- a/modules/dreamview/backend/simulation_world/simulation_world_service_test.cc +++ b/modules/dreamview/backend/simulation_world/simulation_world_service_test.cc @@ -29,7 +29,7 @@ using apollo::canbus::Chassis; using apollo::common::TrajectoryPoint; using apollo::common::monitor::MonitorMessage; using apollo::common::util::StrCat; -using apollo::cybertron::blocker::BlockerManager; +using apollo::cyber::blocker::BlockerManager; using apollo::localization::LocalizationEstimate; using apollo::perception::PerceptionObstacle; using apollo::perception::PerceptionObstacles; @@ -46,10 +46,10 @@ const float kEpsilon = 0.01; class SimulationWorldServiceTest : public ::testing::Test { public: static void SetUpTestCase() { - cybertron::GlobalData::Instance()->EnableSimulationMode(); + cyber::GlobalData::Instance()->EnableSimulationMode(); - std::unique_ptr node = - cybertron::CreateNode("sim_world_service_test"); + std::unique_ptr node = + cyber::CreateNode("sim_world_service_test"); control_writer_ = node->CreateWriter( FLAGS_control_command_topic); } @@ -72,11 +72,11 @@ class SimulationWorldServiceTest : public ::testing::Test { std::unique_ptr sim_world_service_; std::unique_ptr map_service_; - static std::shared_ptr> + static std::shared_ptr> control_writer_; }; -std::shared_ptr> +std::shared_ptr> SimulationWorldServiceTest::control_writer_; TEST_F(SimulationWorldServiceTest, UpdateMonitorSuccess) { diff --git a/modules/dreamview/backend/simulation_world/simulation_world_updater.cc b/modules/dreamview/backend/simulation_world/simulation_world_updater.cc index 68b250346c7..c966deb88f6 100644 --- a/modules/dreamview/backend/simulation_world/simulation_world_updater.cc +++ b/modules/dreamview/backend/simulation_world/simulation_world_updater.cc @@ -318,7 +318,7 @@ bool SimulationWorldUpdater::ValidateCoordinate(const nlohmann::json &json) { } void SimulationWorldUpdater::Start() { - timer_.reset(new cybertron::Timer(kSimWorldTimeIntervalMs, + timer_.reset(new cyber::Timer(kSimWorldTimeIntervalMs, [this]() { this->OnTimer(); }, false)); timer_->Start(); } diff --git a/modules/dreamview/backend/simulation_world/simulation_world_updater.h b/modules/dreamview/backend/simulation_world/simulation_world_updater.h index c475ba70605..e5667154b25 100644 --- a/modules/dreamview/backend/simulation_world/simulation_world_updater.h +++ b/modules/dreamview/backend/simulation_world/simulation_world_updater.h @@ -26,8 +26,8 @@ #include "boost/thread/locks.hpp" #include "boost/thread/shared_mutex.hpp" -#include "cybertron/common/log.h" -#include "cybertron/cybertron.h" +#include "cyber/common/log.h" +#include "cyber/cyber.h" #include "modules/common/util/string_util.h" #include "modules/dreamview/backend/handlers/websocket_handler.h" @@ -122,7 +122,7 @@ class SimulationWorldUpdater { void RegisterMessageHandlers(); - std::unique_ptr timer_; + std::unique_ptr timer_; SimulationWorldService sim_world_service_; const MapService *map_service_ = nullptr; diff --git a/modules/dreamview/launch/dreamview.launch b/modules/dreamview/launch/dreamview.launch index 3b3cfd86e89..248c5b16a91 100644 --- a/modules/dreamview/launch/dreamview.launch +++ b/modules/dreamview/launch/dreamview.launch @@ -1,4 +1,4 @@ - + dreamview @@ -8,4 +8,4 @@ respawn - + diff --git a/modules/dreamview/proto/hmi_config.proto b/modules/dreamview/proto/hmi_config.proto index 239c5834079..d2e4beaf7b2 100644 --- a/modules/dreamview/proto/hmi_config.proto +++ b/modules/dreamview/proto/hmi_config.proto @@ -27,7 +27,7 @@ message Component { } message Launch { - // Major Cybertron components are configured in the launch file. + // Major Cyber components are configured in the launch file. optional string path = 1; // Addtional components besides those in launch file, such as data recorder. repeated string additional_modules = 2; @@ -38,7 +38,7 @@ message Mode { repeated string live_modules = 1 [deprecated = true]; repeated string live_hardware = 2; - // TODO(xiaoxq): Migrate to Cybertron. + // TODO(xiaoxq): Migrate to Cyber. optional string path = 3; // /apollo/modules/calibration/modes/. map launches = 4; // {launch_name: launch_conf} } diff --git a/modules/drivers/camera/BUILD b/modules/drivers/camera/BUILD index 7f7a438da11..e30bb72ac0f 100644 --- a/modules/drivers/camera/BUILD +++ b/modules/drivers/camera/BUILD @@ -25,7 +25,7 @@ cc_library( deps = [ ":camera", "//modules/drivers/proto:sensor_proto", - "//cybertron", + "//cyber", ], copts = ['-DMODULE_NAME=\\"camera\\"'] ) @@ -37,7 +37,7 @@ cc_library( deps = [ "//modules/drivers/proto:sensor_proto", "//modules/drivers/camera/proto:camera_proto", - "//cybertron", + "//cyber", "@opencv2//:core", "@opencv2//:highgui" ], @@ -57,7 +57,7 @@ cc_library( deps = [ "//modules/drivers/camera/proto:camera_proto", - "//cybertron", + "//cyber", "@adv_plat//:adv_plat", ], copts = ['-mavx2'] diff --git a/modules/drivers/camera/camera_component.cc b/modules/drivers/camera/camera_component.cc index b401d627030..6e4d3f5528d 100644 --- a/modules/drivers/camera/camera_component.cc +++ b/modules/drivers/camera/camera_component.cc @@ -22,7 +22,7 @@ namespace camera { bool CameraComponent::Init() { camera_config_ = std::make_shared(); - if (!apollo::cybertron::common::GetProtoFromFile(config_file_path_, + if (!apollo::cyber::common::GetProtoFromFile(config_file_path_, camera_config_.get())) { return false; } @@ -68,15 +68,15 @@ bool CameraComponent::Init() { } writer_ = node_->CreateWriter(camera_config_->channel_name()); - cybertron::Async(&CameraComponent::run, this); + cyber::Async(&CameraComponent::run, this); return true; } void CameraComponent::run() { - while (!cybertron::IsShutdown()) { + while (!cyber::IsShutdown()) { if (!camera_device_->wait_for_device()) { // sleep for next check - cybertron::SleepFor(std::chrono::milliseconds(device_wait_)); + cyber::SleepFor(std::chrono::milliseconds(device_wait_)); continue; } @@ -85,18 +85,18 @@ void CameraComponent::run() { continue; } - cybertron::Time image_time(raw_image_->tv_sec, 1000 * raw_image_->tv_usec); + cyber::Time image_time(raw_image_->tv_sec, 1000 * raw_image_->tv_usec); if (index_ >= buffer_size_) { index_ = 0; } auto pb_image = pb_image_buffer_.at(index_++); pb_image->mutable_header()->set_timestamp_sec( - cybertron::Time::Now().ToSecond()); + cyber::Time::Now().ToSecond()); pb_image->set_measurement_time(image_time.ToSecond()); pb_image->set_data(raw_image_->image, raw_image_->image_size); writer_->Write(pb_image); - cybertron::SleepFor(std::chrono::microseconds(spin_rate_)); + cyber::SleepFor(std::chrono::microseconds(spin_rate_)); } } diff --git a/modules/drivers/camera/camera_component.h b/modules/drivers/camera/camera_component.h index ef35da76cda..c806cb579c1 100644 --- a/modules/drivers/camera/camera_component.h +++ b/modules/drivers/camera/camera_component.h @@ -19,7 +19,7 @@ #include #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/drivers/proto/sensor_image.pb.h" #include "modules/drivers/camera/proto/config.pb.h" @@ -29,9 +29,9 @@ namespace apollo { namespace drivers { namespace camera { -using apollo::cybertron::Component; -using apollo::cybertron::Reader; -using apollo::cybertron::Writer; +using apollo::cyber::Component; +using apollo::cyber::Reader; +using apollo::cyber::Writer; using apollo::drivers::Image; using apollo::drivers::camera::config::Config; @@ -53,7 +53,7 @@ class CameraComponent : public Component<> { int buffer_size_ = 8; }; -CYBERTRON_REGISTER_COMPONENT(CameraComponent) +CYBER_REGISTER_COMPONENT(CameraComponent) } // namespace camera } // namespace drivers } // namespace apollo diff --git a/modules/drivers/camera/compress_component.h b/modules/drivers/camera/compress_component.h index 68adca5acb0..ad739d3646f 100644 --- a/modules/drivers/camera/compress_component.h +++ b/modules/drivers/camera/compress_component.h @@ -18,8 +18,8 @@ #include -#include "cybertron/base/concurrent_object_pool.h" -#include "cybertron/cybertron.h" +#include "cyber/base/concurrent_object_pool.h" +#include "cyber/cyber.h" #include "modules/drivers/camera/proto/config.pb.h" #include "modules/drivers/proto/sensor_image.pb.h" @@ -27,9 +27,9 @@ namespace apollo { namespace drivers { namespace camera { -using apollo::cybertron::Component; -using apollo::cybertron::Writer; -using apollo::cybertron::base::CCObjectPool; +using apollo::cyber::Component; +using apollo::cyber::Writer; +using apollo::cyber::base::CCObjectPool; using apollo::drivers::Image; using apollo::drivers::camera::config::Config; @@ -44,7 +44,7 @@ class CompressComponent : public Component { Config config_; }; -CYBERTRON_REGISTER_COMPONENT(CompressComponent) +CYBER_REGISTER_COMPONENT(CompressComponent) } // namespace camera } // namespace drivers } // namespace apollo diff --git a/modules/drivers/camera/launch/camera.launch b/modules/drivers/camera/launch/camera.launch index 96981a850b3..340262899f2 100644 --- a/modules/drivers/camera/launch/camera.launch +++ b/modules/drivers/camera/launch/camera.launch @@ -1,7 +1,7 @@ - + camera /apollo/modules/drivers/camera/dag/camera.dag usb_cam - + diff --git a/modules/drivers/camera/usb_cam.cc b/modules/drivers/camera/usb_cam.cc index 95830354605..7eba41e885a 100644 --- a/modules/drivers/camera/usb_cam.cc +++ b/modules/drivers/camera/usb_cam.cc @@ -792,7 +792,7 @@ bool UsbCam::read_frame(CameraImagePtr raw_image) { raw_image->tv_usec = buf.timestamp.tv_usec; { - cybertron::Time image_time(raw_image->tv_sec, + cyber::Time image_time(raw_image->tv_sec, 1000 * raw_image->tv_usec); uint64_t camera_timestamp = image_time.ToNanosecond(); if (last_nsec_ == 0) { @@ -814,7 +814,7 @@ bool UsbCam::read_frame(CameraImagePtr raw_image) { last_nsec_ = camera_timestamp; } - double now_s = cybertron::Time::Now().ToSecond(); + double now_s = cyber::Time::Now().ToSecond(); double image_s = camera_timestamp / 1e9; double diff = now_s - image_s; if (diff > 0.5 || diff < 0) { diff --git a/modules/drivers/camera/usb_cam.h b/modules/drivers/camera/usb_cam.h index b3010d9800b..e9dd97cee93 100644 --- a/modules/drivers/camera/usb_cam.h +++ b/modules/drivers/camera/usb_cam.h @@ -60,7 +60,7 @@ extern "C" { #include #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/drivers/camera/proto/config.pb.h" diff --git a/modules/drivers/canbus/can_client/BUILD b/modules/drivers/canbus/can_client/BUILD index a544b10ce55..179af9d2608 100644 --- a/modules/drivers/canbus/can_client/BUILD +++ b/modules/drivers/canbus/can_client/BUILD @@ -11,7 +11,7 @@ cc_library( "can_client_factory.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/drivers/canbus/can_client", "//modules/drivers/canbus/common:canbus_common", "//modules/drivers/canbus/proto:canbus_proto", diff --git a/modules/drivers/canbus/can_client/can_client.h b/modules/drivers/canbus/can_client/can_client.h index 44362c0fb77..b903dfcc84c 100644 --- a/modules/drivers/canbus/can_client/can_client.h +++ b/modules/drivers/canbus/can_client/can_client.h @@ -27,7 +27,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/proto/error_code.pb.h" #include "modules/drivers/canbus/common/byte.h" #include "modules/drivers/canbus/proto/can_card_parameter.pb.h" diff --git a/modules/drivers/canbus/can_client/can_client_factory.cc b/modules/drivers/canbus/can_client/can_client_factory.cc index 954136dc768..d2463f5a7e1 100644 --- a/modules/drivers/canbus/can_client/can_client_factory.cc +++ b/modules/drivers/canbus/can_client/can_client_factory.cc @@ -25,7 +25,7 @@ #include "modules/drivers/canbus/can_client/hermes_can/hermes_can_client.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/util.h" namespace apollo { diff --git a/modules/drivers/canbus/can_client/can_client_factory.h b/modules/drivers/canbus/can_client/can_client_factory.h index 38ec58b6e35..2a2a1ea65a2 100644 --- a/modules/drivers/canbus/can_client/can_client_factory.h +++ b/modules/drivers/canbus/can_client/can_client_factory.h @@ -24,7 +24,7 @@ #include #include -#include "cybertron/common/macros.h" +#include "cyber/common/macros.h" #include "modules/common/util/factory.h" #include "modules/drivers/canbus/can_client/can_client.h" diff --git a/modules/drivers/canbus/can_client/can_client_tool.cc b/modules/drivers/canbus/can_client/can_client_tool.cc index 01a590adb90..9dc34de92af 100644 --- a/modules/drivers/canbus/can_client/can_client_tool.cc +++ b/modules/drivers/canbus/can_client/can_client_tool.cc @@ -20,7 +20,7 @@ #include #include "gflags/gflags.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/proto/error_code.pb.h" #include "modules/common/time/time.h" #include "modules/common/util/factory.h" diff --git a/modules/drivers/canbus/can_client/esd/BUILD b/modules/drivers/canbus/can_client/esd/BUILD index b275416c6fb..0805776043f 100644 --- a/modules/drivers/canbus/can_client/esd/BUILD +++ b/modules/drivers/canbus/can_client/esd/BUILD @@ -23,7 +23,7 @@ cc_test( "esd_can_client_test.cc", ], deps = [ - "//cybertron", + "//cyber", "//modules/drivers/canbus/can_client/esd:esd_can_client", "//modules/drivers/canbus/common:canbus_common", "@gtest//:main", diff --git a/modules/drivers/canbus/can_client/fake/BUILD b/modules/drivers/canbus/can_client/fake/BUILD index d804114d964..cc8d62d977a 100644 --- a/modules/drivers/canbus/can_client/fake/BUILD +++ b/modules/drivers/canbus/can_client/fake/BUILD @@ -22,7 +22,7 @@ cc_test( "fake_can_client_test.cc", ], deps = [ - "//cybertron", + "//cyber", "//modules/drivers/canbus/can_client/fake:fake_can_client", "//modules/drivers/canbus/common:canbus_common", "@gtest//:main", diff --git a/modules/drivers/canbus/can_client/fake/fake_can_client_test.cc b/modules/drivers/canbus/can_client/fake/fake_can_client_test.cc index 702c6b1e092..e9071e164a4 100644 --- a/modules/drivers/canbus/can_client/fake/fake_can_client_test.cc +++ b/modules/drivers/canbus/can_client/fake/fake_can_client_test.cc @@ -23,7 +23,7 @@ #include "gtest/gtest.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/time/time.h" #include "modules/drivers/canbus/common/byte.h" diff --git a/modules/drivers/canbus/can_client/hermes_can/BUILD b/modules/drivers/canbus/can_client/hermes_can/BUILD index 036f7ae51f5..6b13a87cdec 100644 --- a/modules/drivers/canbus/can_client/hermes_can/BUILD +++ b/modules/drivers/canbus/can_client/hermes_can/BUILD @@ -25,7 +25,7 @@ cc_test( "hermes_can_client_test.cc", ], deps = [ - "//cybertron", + "//cyber", "//modules/drivers/canbus/can_client/hermes_can:hermes_can_client", "//modules/drivers/canbus/common:canbus_common", "@gtest//:main", diff --git a/modules/drivers/canbus/can_client/socket/BUILD b/modules/drivers/canbus/can_client/socket/BUILD index dd51113e40b..052e21a58a2 100644 --- a/modules/drivers/canbus/can_client/socket/BUILD +++ b/modules/drivers/canbus/can_client/socket/BUILD @@ -22,7 +22,7 @@ cc_test( "socket_can_client_raw_test.cc", ], deps = [ - "//cybertron", + "//cyber", "//modules/drivers/canbus/can_client/socket:socket_can_client_raw", "//modules/drivers/canbus/common:canbus_common", "@gtest//:main", diff --git a/modules/drivers/canbus/can_comm/BUILD b/modules/drivers/canbus/can_comm/BUILD index e3e514ceacc..85da23f3d49 100644 --- a/modules/drivers/canbus/can_comm/BUILD +++ b/modules/drivers/canbus/can_comm/BUILD @@ -45,7 +45,7 @@ cc_test( "can_sender_test.cc", ], deps = [ - "//cybertron", + "//cyber", "//modules/canbus/proto:canbus_proto", "//modules/drivers/canbus/can_client/fake:fake_can_client", "//modules/drivers/canbus/can_comm:can_sender", @@ -61,7 +61,7 @@ cc_test( "can_receiver_test.cc", ], deps = [ - "//cybertron", + "//cyber", "//modules/canbus/proto:canbus_proto", "//modules/drivers/canbus/can_client/fake:fake_can_client", "//modules/drivers/canbus/can_comm:can_receiver", @@ -88,7 +88,7 @@ cc_test( size = "small", srcs = ["message_manager_test.cc"], deps = [ - "//cybertron", + "//cyber", "//modules/canbus/proto:canbus_proto", "//modules/drivers/canbus/can_comm:message_manager_base", "@gtest//:main", diff --git a/modules/drivers/canbus/can_comm/can_receiver.h b/modules/drivers/canbus/can_comm/can_receiver.h index 35116682b98..cb0e303c724 100644 --- a/modules/drivers/canbus/can_comm/can_receiver.h +++ b/modules/drivers/canbus/can_comm/can_receiver.h @@ -28,8 +28,8 @@ #include #include -#include "cybertron/common/macros.h" -#include "cybertron/cybertron.h" +#include "cyber/common/macros.h" +#include "cyber/cyber.h" #include "modules/common/proto/error_code.pb.h" @@ -146,7 +146,7 @@ void CanReceiver::RecvThreadFunc() { LOG_IF_EVERY_N(ERROR, receive_error_count++ > ERROR_COUNT_MAX, ERROR_COUNT_MAX) << "Received " << receive_error_count << " error messages."; - cybertron::USleep(default_period); + cyber::USleep(default_period); continue; } receive_error_count = 0; @@ -161,7 +161,7 @@ void CanReceiver::RecvThreadFunc() { LOG_IF_EVERY_N(ERROR, receive_none_count++ > ERROR_COUNT_MAX, ERROR_COUNT_MAX) << "Received " << receive_none_count << " empty messages."; - cybertron::USleep(default_period); + cyber::USleep(default_period); continue; } receive_none_count = 0; @@ -175,7 +175,7 @@ void CanReceiver::RecvThreadFunc() { ADEBUG << "recv_can_frame#" << frame.CanFrameString(); } } - cybertron::Yield(); + cyber::Yield(); } AINFO << "Can client receiver thread stopped."; } @@ -192,7 +192,7 @@ ::apollo::common::ErrorCode CanReceiver::Start() { } is_running_ = true; - cybertron::Async(&CanReceiver::RecvThreadFunc, this); + cyber::Async(&CanReceiver::RecvThreadFunc, this); return ::apollo::common::ErrorCode::OK; } diff --git a/modules/drivers/canbus/can_comm/can_receiver_test.cc b/modules/drivers/canbus/can_comm/can_receiver_test.cc index 1d21891825e..fbd63a38ed6 100644 --- a/modules/drivers/canbus/can_comm/can_receiver_test.cc +++ b/modules/drivers/canbus/can_comm/can_receiver_test.cc @@ -28,7 +28,7 @@ namespace drivers { namespace canbus { TEST(CanReceiverTest, ReceiveOne) { - cybertron::Init(); + cyber::Init(); can::FakeCanClient can_client; MessageManager<::apollo::canbus::ChassisDetail> pm; CanReceiver<::apollo::canbus::ChassisDetail> receiver; @@ -38,7 +38,7 @@ TEST(CanReceiverTest, ReceiveOne) { EXPECT_TRUE(receiver.IsRunning()); receiver.Stop(); EXPECT_FALSE(receiver.IsRunning()); - cybertron::Shutdown(); + cyber::Shutdown(); } } // namespace canbus diff --git a/modules/drivers/canbus/can_comm/can_sender.h b/modules/drivers/canbus/can_comm/can_sender.h index 9cd9fcccd43..a60df05d360 100644 --- a/modules/drivers/canbus/can_comm/can_sender.h +++ b/modules/drivers/canbus/can_comm/can_sender.h @@ -31,9 +31,9 @@ #include "gtest/gtest_prod.h" -#include "cybertron/common/macros.h" +#include "cyber/common/macros.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/proto/error_code.pb.h" #include "modules/common/time/time.h" #include "modules/drivers/canbus/can_client/can_client.h" diff --git a/modules/drivers/canbus/can_comm/message_manager.h b/modules/drivers/canbus/can_comm/message_manager.h index bb75df3c02c..b0b2e5ba8f2 100644 --- a/modules/drivers/canbus/can_comm/message_manager.h +++ b/modules/drivers/canbus/can_comm/message_manager.h @@ -28,7 +28,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/proto/error_code.pb.h" #include "modules/common/time/time.h" #include "modules/drivers/canbus/can_comm/protocol_data.h" diff --git a/modules/drivers/canbus/can_comm/protocol_data.h b/modules/drivers/canbus/can_comm/protocol_data.h index b89570060cf..ce08ec111d4 100644 --- a/modules/drivers/canbus/can_comm/protocol_data.h +++ b/modules/drivers/canbus/can_comm/protocol_data.h @@ -24,7 +24,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/drivers/canbus/common/canbus_consts.h" /** diff --git a/modules/drivers/canbus/sensor_canbus.h b/modules/drivers/canbus/sensor_canbus.h index 0d422f3fdcd..58631b91685 100644 --- a/modules/drivers/canbus/sensor_canbus.h +++ b/modules/drivers/canbus/sensor_canbus.h @@ -28,7 +28,7 @@ #include #include -#include "cybertron/component/component.h" +#include "cyber/component/component.h" #include "modules/common/adapters/adapter_manager.h" #include "modules/common/adapters/proto/adapter_config.pb.h" @@ -69,7 +69,7 @@ using apollo::drivers::canbus::CanReceiver; using apollo::drivers::canbus::SensorCanbusConf; template -class SensorCanbus : public apollo::cybertron::Component { +class SensorCanbus : public apollo::cyber::Component { public: // TODO(lizh): check whether we need a new msg item, say // MonitorMessageItem::SENSORCANBUS @@ -160,7 +160,7 @@ bool SensorCanbus::Start() { // no need for timer. if (FLAGS_sensor_freq > 0) { const double duration_ms = 1000.0 / FLAGS_sensor_freq; - timer_ = cybertron::Timer(duration_ms, &SensorCanbus::OnTimer, + timer_ = cyber::Timer(duration_ms, &SensorCanbus::OnTimer, this, false); timer_.Start(); } else { diff --git a/modules/drivers/gnss/BUILD b/modules/drivers/gnss/BUILD index fa4de3c66cb..9c984a1271b 100644 --- a/modules/drivers/gnss/BUILD +++ b/modules/drivers/gnss/BUILD @@ -16,7 +16,7 @@ cc_library( deps = [ "//modules/drivers/gnss/stream:gnss_stream", "//modules/common/monitor_log", - "//cybertron", + "//cyber", ], copts = ['-DMODULE_NAME=\\"gnss\\"'] ) diff --git a/modules/drivers/gnss/gnss_component.cc b/modules/drivers/gnss/gnss_component.cc index 951b9f20c3d..b53421db506 100644 --- a/modules/drivers/gnss/gnss_component.cc +++ b/modules/drivers/gnss/gnss_component.cc @@ -19,7 +19,7 @@ namespace apollo { namespace drivers { namespace gnss { -using apollo::cybertron::proto::RoleAttributes; +using apollo::cyber::proto::RoleAttributes; GnssDriverComponent::GnssDriverComponent() : monitor_logger_buffer_( @@ -27,7 +27,7 @@ GnssDriverComponent::GnssDriverComponent() bool GnssDriverComponent::Init() { config::Config gnss_config; - if (!apollo::cybertron::common::GetProtoFromFile(config_file_path_, + if (!apollo::cyber::common::GetProtoFromFile(config_file_path_, &gnss_config)) { monitor_logger_buffer_.ERROR( "Unable to load gnss conf file: " + config_file_path_); diff --git a/modules/drivers/gnss/gnss_component.h b/modules/drivers/gnss/gnss_component.h index 512eeee1b03..00985d3c449 100644 --- a/modules/drivers/gnss/gnss_component.h +++ b/modules/drivers/gnss/gnss_component.h @@ -19,7 +19,7 @@ #include #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/common/monitor_log/monitor_log_buffer.h" #include "modules/drivers/gnss/stream/raw_stream.h" @@ -28,9 +28,9 @@ namespace apollo { namespace drivers { namespace gnss { -using apollo::cybertron::Component; -using apollo::cybertron::Reader; -using apollo::cybertron::Writer; +using apollo::cyber::Component; +using apollo::cyber::Reader; +using apollo::cyber::Writer; using apollo::drivers::gnss::RawData; class GnssDriverComponent : public Component<> { @@ -43,7 +43,7 @@ class GnssDriverComponent : public Component<> { apollo::common::monitor::MonitorLogBuffer monitor_logger_buffer_; }; -CYBERTRON_REGISTER_COMPONENT(GnssDriverComponent) +CYBER_REGISTER_COMPONENT(GnssDriverComponent) } // namespace gnss } // namespace drivers diff --git a/modules/drivers/gnss/launch/gnss.launch b/modules/drivers/gnss/launch/gnss.launch index 262cb524cda..e9c1abb5884 100644 --- a/modules/drivers/gnss/launch/gnss.launch +++ b/modules/drivers/gnss/launch/gnss.launch @@ -1,7 +1,7 @@ - + gnss /apollo/modules/drivers/gnss/dag/gnss.dag gnss - + diff --git a/modules/drivers/gnss/parser/BUILD b/modules/drivers/gnss/parser/BUILD index 479dfbd418b..ee04b2d8aa4 100644 --- a/modules/drivers/gnss/parser/BUILD +++ b/modules/drivers/gnss/parser/BUILD @@ -28,7 +28,7 @@ cc_library( "//modules/localization/proto:imu_proto", "//modules/transform:transform_broadcaster_lib", "@proj4", - "//cybertron", + "//cyber", "@eigen", ], ) @@ -46,7 +46,7 @@ cc_library( "//modules/drivers/gnss/proto:gnss_proto", "//modules/drivers/gnss/third_party:rtcm", "//modules/drivers/gnss/util:gnss_util", - "//cybertron", + "//cyber", ], ) @@ -67,7 +67,7 @@ cc_library( "//modules/drivers/gnss/proto:gnss_proto", "//modules/drivers/gnss/third_party:rtcm", "//modules/drivers/gnss/util:gnss_util", - "//cybertron", + "//cyber", ], ) diff --git a/modules/drivers/gnss/parser/data_parser.cc b/modules/drivers/gnss/parser/data_parser.cc index 4bf7a065d61..d4a27ef175b 100644 --- a/modules/drivers/gnss/parser/data_parser.cc +++ b/modules/drivers/gnss/parser/data_parser.cc @@ -22,7 +22,7 @@ #include "Eigen/Geometry" #include "boost/array.hpp" -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/common/adapters/adapter_gflags.h" #include "modules/common/util/message_util.h" #include "modules/drivers/gnss/proto/gnss_best_pose.pb.h" @@ -65,7 +65,7 @@ Parser *CreateParser(config::Config config, bool is_base_station = false) { } // namespace DataParser::DataParser(const config::Config &config, - const std::shared_ptr &node) + const std::shared_ptr &node) : config_(config), tf_broadcaster_(node), node_(node) { std::string utm_target_param; @@ -80,9 +80,9 @@ DataParser::DataParser(const config::Config &config, bool DataParser::Init() { ins_status_.mutable_header()->set_timestamp_sec( - cybertron::Time::Now().ToSecond()); + cyber::Time::Now().ToSecond()); gnss_status_.mutable_header()->set_timestamp_sec( - cybertron::Time::Now().ToSecond()); + cyber::Time::Now().ToSecond()); gnssstatus_writer_ = node_->CreateWriter(FLAGS_gnss_status_topic); insstatus_writer_ = node_->CreateWriter(FLAGS_ins_status_topic); @@ -124,7 +124,7 @@ void DataParser::ParseRawData(const std::string &msg) { Parser::MessageType type; MessagePtr msg_ptr; - while (cybertron::OK()) { + while (cyber::OK()) { type = data_parser_->GetMessage(&msg_ptr); if (type == Parser::MessageType::NONE) break; DispatchMessage(type, msg_ptr); diff --git a/modules/drivers/gnss/parser/data_parser.h b/modules/drivers/gnss/parser/data_parser.h index d52209f2321..2526e7015fa 100644 --- a/modules/drivers/gnss/parser/data_parser.h +++ b/modules/drivers/gnss/parser/data_parser.h @@ -20,7 +20,7 @@ #include #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/transform/transform_broadcaster.h" #include "modules/drivers/gnss/proto/config.pb.h" @@ -44,7 +44,7 @@ class DataParser { public: using MessagePtr = ::google::protobuf::Message *; explicit DataParser(const config::Config &config, - const std::shared_ptr &node); + const std::shared_ptr &node); ~DataParser() {} bool Init(); void ParseRawData(const std::string &msg); @@ -76,24 +76,24 @@ class DataParser { projPJ wgs84pj_source_; projPJ utm_target_; - std::shared_ptr node_ = nullptr; - std::shared_ptr> gnssstatus_writer_ = + std::shared_ptr node_ = nullptr; + std::shared_ptr> gnssstatus_writer_ = nullptr; - std::shared_ptr> insstatus_writer_ = + std::shared_ptr> insstatus_writer_ = nullptr; - std::shared_ptr> + std::shared_ptr> gnssbestpose_writer_ = nullptr; - std::shared_ptr> + std::shared_ptr> corrimu_writer_ = nullptr; - std::shared_ptr> rawimu_writer_ = nullptr; - std::shared_ptr> + std::shared_ptr> rawimu_writer_ = nullptr; + std::shared_ptr> gps_writer_ = nullptr; - std::shared_ptr> insstat_writer_ = nullptr; - std::shared_ptr> + std::shared_ptr> insstat_writer_ = nullptr; + std::shared_ptr> gnssephemeris_writer_ = nullptr; - std::shared_ptr> + std::shared_ptr> epochobservation_writer_ = nullptr; - std::shared_ptr> heading_writer_ = nullptr; + std::shared_ptr> heading_writer_ = nullptr; }; } // namespace gnss diff --git a/modules/drivers/gnss/parser/novatel_parser.cc b/modules/drivers/gnss/parser/novatel_parser.cc index 60d1ff37300..cf51fc3ddca 100644 --- a/modules/drivers/gnss/parser/novatel_parser.cc +++ b/modules/drivers/gnss/parser/novatel_parser.cc @@ -24,7 +24,7 @@ #include #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/drivers/gnss/parser/novatel_messages.h" #include "modules/drivers/gnss/parser/parser.h" @@ -647,7 +647,7 @@ bool NovatelParser::HandleCorrImuData(const novatel::CorrImuData* imu) { return false; } - ins_.mutable_header()->set_timestamp_sec(cybertron::Time::Now().ToSecond()); + ins_.mutable_header()->set_timestamp_sec(cyber::Time::Now().ToSecond()); return true; } @@ -696,7 +696,7 @@ bool NovatelParser::HandleInsPva(const novatel::InsPva* pva) { return false; } - ins_.mutable_header()->set_timestamp_sec(cybertron::Time::Now().ToSecond()); + ins_.mutable_header()->set_timestamp_sec(cyber::Time::Now().ToSecond()); return true; } diff --git a/modules/drivers/gnss/parser/rtcm3_parser.h b/modules/drivers/gnss/parser/rtcm3_parser.h index 79ae16e223e..0398a8cbfab 100644 --- a/modules/drivers/gnss/parser/rtcm3_parser.h +++ b/modules/drivers/gnss/parser/rtcm3_parser.h @@ -25,7 +25,7 @@ #include "modules/drivers/gnss/proto/gnss_raw_observation.pb.h" -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/drivers/gnss/parser/parser.h" #include "modules/drivers/gnss/parser/rtcm_decode.h" diff --git a/modules/drivers/gnss/parser/rtcm_parser.cc b/modules/drivers/gnss/parser/rtcm_parser.cc index 6e7cceb3a34..5978406db67 100644 --- a/modules/drivers/gnss/parser/rtcm_parser.cc +++ b/modules/drivers/gnss/parser/rtcm_parser.cc @@ -18,7 +18,7 @@ #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/common/adapters/adapter_gflags.h" #include "modules/drivers/gnss/parser/parser.h" #include "modules/drivers/gnss/parser/rtcm3_parser.h" @@ -32,7 +32,7 @@ using ::apollo::drivers::gnss::EpochObservation; using ::apollo::drivers::gnss::GnssEphemeris; RtcmParser::RtcmParser(const config::Config& config, - const std::shared_ptr& node) + const std::shared_ptr& node) : config_(config), node_(node) {} bool RtcmParser::Init() { @@ -60,7 +60,7 @@ void RtcmParser::ParseRtcmData(const std::string& msg) { Parser::MessageType type; MessagePtr msg_ptr; - while (cybertron::OK()) { + while (cyber::OK()) { type = rtcm_parser_->GetMessage(&msg_ptr); if (type == Parser::MessageType::NONE) break; DispatchMessage(type, msg_ptr); diff --git a/modules/drivers/gnss/parser/rtcm_parser.h b/modules/drivers/gnss/parser/rtcm_parser.h index 8035e568b7b..1dce617e535 100644 --- a/modules/drivers/gnss/parser/rtcm_parser.h +++ b/modules/drivers/gnss/parser/rtcm_parser.h @@ -19,7 +19,7 @@ #include #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/drivers/gnss/parser/parser.h" @@ -33,7 +33,7 @@ class RtcmParser { public: using MessagePtr = ::google::protobuf::Message*; RtcmParser(const config::Config& config, - const std::shared_ptr& node); + const std::shared_ptr& node); ~RtcmParser() {} bool Init(); void ParseRtcmData(const std::string& msg); @@ -44,10 +44,10 @@ class RtcmParser { void PublishObservation(const MessagePtr& message); config::Config config_; - std::shared_ptr node_ = nullptr; - std::shared_ptr> + std::shared_ptr node_ = nullptr; + std::shared_ptr> gnssephemeris_writer_ = nullptr; - std::shared_ptr> + std::shared_ptr> epochobservation_writer_ = nullptr; bool init_flag_ = false; std::unique_ptr rtcm_parser_ = nullptr; diff --git a/modules/drivers/gnss/stream/BUILD b/modules/drivers/gnss/stream/BUILD index 742ea6940c7..ea4c7b5ec01 100644 --- a/modules/drivers/gnss/stream/BUILD +++ b/modules/drivers/gnss/stream/BUILD @@ -24,7 +24,7 @@ cc_library( "//modules/common/proto:pnc_point_proto", "//modules/common/util:util", "//modules/common/math:math", - "//cybertron", + "//cyber", ], ) @@ -42,7 +42,7 @@ cc_library( "//modules/canbus/proto:canbus_proto", "//modules/drivers/gnss/util:gnss_util", "//modules/common/util:message_util", - "//cybertron", + "//cyber", ], ) @@ -52,7 +52,7 @@ cc_library( deps = [ ":stream", "//modules/drivers/gnss/util:gnss_util", - "//cybertron", + "//cyber", ], ) @@ -62,7 +62,7 @@ cc_library( hdrs = ["tcp_stream.h"], deps = [ ":stream", - "//cybertron", + "//cyber", ], ) @@ -72,7 +72,7 @@ cc_library( deps = [ ":stream", "//modules/drivers/gnss/util:gnss_util", - "//cybertron", + "//cyber", ], ) @@ -81,7 +81,7 @@ cc_library( hdrs = ["stream.h"], deps = [ "//modules/drivers/gnss/util:gnss_util", - "//cybertron", + "//cyber", ], ) diff --git a/modules/drivers/gnss/stream/ntrip_stream.cc b/modules/drivers/gnss/stream/ntrip_stream.cc index deda816bbae..d49aed16e12 100644 --- a/modules/drivers/gnss/stream/ntrip_stream.cc +++ b/modules/drivers/gnss/stream/ntrip_stream.cc @@ -18,7 +18,7 @@ #include #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/common/util/string_util.h" #include "modules/common/util/util.h" @@ -172,7 +172,7 @@ void NtripStream::Reconnect() { return; } - data_active_s_ = cybertron::Time::Now().ToSecond(); + data_active_s_ = cyber::Time::Now().ToSecond(); AINFO << "Reconnect ntrip caster success."; } @@ -191,16 +191,16 @@ size_t NtripStream::read(uint8_t* buffer, size_t max_length) { } if (is_zero(data_active_s_)) { - data_active_s_ = cybertron::Time::Now().ToSecond(); + data_active_s_ = cyber::Time::Now().ToSecond(); } ret = tcp_stream_->read(buffer, max_length); if (ret) { - data_active_s_ = cybertron::Time::Now().ToSecond(); + data_active_s_ = cyber::Time::Now().ToSecond(); } // timeout detect - if ((cybertron::Time::Now().ToSecond() - data_active_s_) > timeout_s_) { + if ((cyber::Time::Now().ToSecond() - data_active_s_) > timeout_s_) { AINFO << "Ntrip timeout."; Reconnect(); } diff --git a/modules/drivers/gnss/stream/raw_stream.cc b/modules/drivers/gnss/stream/raw_stream.cc index fe326f1afd1..c14e874924d 100644 --- a/modules/drivers/gnss/stream/raw_stream.cc +++ b/modules/drivers/gnss/stream/raw_stream.cc @@ -20,7 +20,7 @@ #include #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/common/adapters/adapter_gflags.h" #include "modules/common/util/message_util.h" #include "modules/drivers/gnss/proto/config.pb.h" @@ -56,7 +56,7 @@ std::string getLocalTimeFileStr(const std::string &gpsbin_folder) { std::strftime(local_time_char, sizeof(local_time_char), "%Y%m%d_%H%M%S", localtime(&it)); std::string local_time_str = local_time_char; - CHECK(cybertron::common::EnsureDirectory(gpsbin_folder)) + CHECK(cyber::common::EnsureDirectory(gpsbin_folder)) << "gbsbin folder : " << gpsbin_folder << " create fail"; std::string local_time_file_str = gpsbin_folder + "/" + local_time_str + ".bin"; @@ -130,7 +130,7 @@ Stream *create_stream(const config::Stream &sd) { } RawStream::RawStream(const config::Config &config, - const std::shared_ptr &node) + const std::shared_ptr &node) : config_(config), node_(node) { data_parser_ptr_.reset(new DataParser(config_, node_)); rtcm_parser_ptr_.reset(new RtcmParser(config_, node_)); @@ -272,7 +272,7 @@ bool RawStream::Init() { node_->CreateWriter(FLAGS_stream_status_topic); raw_writer_ = node_->CreateWriter(FLAGS_gnss_raw_data_topic); rtcm_writer_ = node_->CreateWriter(FLAGS_rtcm_data_topic); - cybertron::ReaderConfig reader_config; + cyber::ReaderConfig reader_config; reader_config.channel_name = FLAGS_gnss_raw_data_topic; reader_config.pending_queue_size = 100; gpsbin_reader_ = node_->CreateReader(reader_config, @@ -290,7 +290,7 @@ void RawStream::Start() { data_thread_ptr_.reset(new std::thread(&RawStream::DataSpin, this)); rtk_thread_ptr_.reset(new std::thread(&RawStream::RtkSpin, this)); if (config_.has_wheel_parameters()) { - wheel_velocity_timer_.reset(new cybertron::Timer( + wheel_velocity_timer_.reset(new cyber::Timer( 1000, [this]() { this->OnWheelVelocityTimer(); }, false)); wheel_velocity_timer_->Start(); } @@ -301,7 +301,7 @@ void RawStream::OnWheelVelocityTimer() { AINFO << "No chassis message received"; return; } - auto latency_sec = cybertron::Time::Now().ToSecond() - + auto latency_sec = cyber::Time::Now().ToSecond() - chassis_ptr_->header().timestamp_sec(); auto latency_ms = std::to_string(std::lround(latency_sec * 1000)); auto speed_cmps = @@ -407,7 +407,7 @@ bool RawStream::Login() { login_data.emplace_back(login_command); AINFO << "Login command: " << login_command; // sleep a little to avoid overrun of the slow serial interface. - cybertron::Duration(0.5).Sleep(); + cyber::Duration(0.5).Sleep(); } data_stream_->RegisterLoginData(login_data); @@ -464,7 +464,7 @@ void RawStream::StreamStatusCheck() { void RawStream::DataSpin() { common::util::FillHeader("gnss", &stream_status_); stream_writer_->Write(std::make_shared(stream_status_)); - while (cybertron::OK()) { + while (cyber::OK()) { size_t length = data_stream_->read(buffer_, BUFFER_SIZE); if (length > 0) { std::shared_ptr msg_pub = std::make_shared(); @@ -487,7 +487,7 @@ void RawStream::RtkSpin() { if (in_rtk_stream_ == nullptr) { return; } - while (cybertron::OK()) { + while (cyber::OK()) { size_t length = in_rtk_stream_->read(buffer_rtk_, BUFFER_SIZE); if (length > 0) { if (rtk_software_solution_) { diff --git a/modules/drivers/gnss/stream/raw_stream.h b/modules/drivers/gnss/stream/raw_stream.h index 7fedc4137a5..c1b35901107 100644 --- a/modules/drivers/gnss/stream/raw_stream.h +++ b/modules/drivers/gnss/stream/raw_stream.h @@ -21,7 +21,7 @@ #include #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/canbus/proto/chassis.pb.h" #include "modules/drivers/gnss/proto/config.pb.h" @@ -38,7 +38,7 @@ namespace gnss { class RawStream { public: explicit RawStream(const config::Config& config, - const std::shared_ptr& node); + const std::shared_ptr& node); ~RawStream(); bool Init(); @@ -63,7 +63,7 @@ class RawStream { void GpsbinCallback(const std::shared_ptr& raw_data); void OnWheelVelocityTimer(); - std::unique_ptr wheel_velocity_timer_ = nullptr; + std::unique_ptr wheel_velocity_timer_ = nullptr; std::shared_ptr chassis_ptr_ = nullptr; static constexpr size_t BUFFER_SIZE = 2048; uint8_t buffer_[BUFFER_SIZE] = {0}; @@ -95,13 +95,13 @@ class RawStream { std::unique_ptr gpsbin_thread_ptr_; std::unique_ptr gpsbin_stream_ = nullptr; - std::shared_ptr node_ = nullptr; - std::shared_ptr> stream_writer_ = + std::shared_ptr node_ = nullptr; + std::shared_ptr> stream_writer_ = nullptr; - std::shared_ptr> raw_writer_ = nullptr; - std::shared_ptr> rtcm_writer_ = nullptr; - std::shared_ptr> gpsbin_reader_ = nullptr; - std::shared_ptr> + std::shared_ptr> raw_writer_ = nullptr; + std::shared_ptr> rtcm_writer_ = nullptr; + std::shared_ptr> gpsbin_reader_ = nullptr; + std::shared_ptr> chassis_reader_ = nullptr; }; diff --git a/modules/drivers/gnss/stream/serial_stream.cc b/modules/drivers/gnss/stream/serial_stream.cc index 5067e624d59..e2c6e710e17 100644 --- a/modules/drivers/gnss/stream/serial_stream.cc +++ b/modules/drivers/gnss/stream/serial_stream.cc @@ -28,7 +28,7 @@ #include #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/drivers/gnss/stream/stream.h" diff --git a/modules/drivers/gnss/stream/stream.h b/modules/drivers/gnss/stream/stream.h index 5eeeab011a9..086fa512fef 100644 --- a/modules/drivers/gnss/stream/stream.h +++ b/modules/drivers/gnss/stream/stream.h @@ -21,7 +21,7 @@ #include #include #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/drivers/gnss/util/macros.h" @@ -79,7 +79,7 @@ class Stream { write(login_data_[i]); AINFO << "Login: " << login_data_[i]; // sleep a little to avoid overrun of the slow serial interface. - cybertron::Duration(0.5).Sleep(); + cyber::Duration(0.5).Sleep(); } } diff --git a/modules/drivers/gnss/stream/tcp_stream.cc b/modules/drivers/gnss/stream/tcp_stream.cc index f2fcd5bc221..18e2a2387a5 100644 --- a/modules/drivers/gnss/stream/tcp_stream.cc +++ b/modules/drivers/gnss/stream/tcp_stream.cc @@ -26,7 +26,7 @@ #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/drivers/gnss/stream/stream.h" #include "modules/drivers/gnss/stream/tcp_stream.h" diff --git a/modules/drivers/gnss/stream/udp_stream.cc b/modules/drivers/gnss/stream/udp_stream.cc index a5dd83559f5..3a3f6fb9597 100644 --- a/modules/drivers/gnss/stream/udp_stream.cc +++ b/modules/drivers/gnss/stream/udp_stream.cc @@ -22,7 +22,7 @@ #include #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/drivers/gnss/stream/stream.h" diff --git a/modules/drivers/gnss/test/BUILD b/modules/drivers/gnss/test/BUILD index 39ffdcada8d..de78803ac4b 100644 --- a/modules/drivers/gnss/test/BUILD +++ b/modules/drivers/gnss/test/BUILD @@ -8,7 +8,7 @@ cc_binary( deps = [ "//modules/drivers/gnss/stream:gnss_stream", "//external:gflags", - "//cybertron", + "//cyber", "@ros//:ros_common", ], ) diff --git a/modules/drivers/gnss/test/parser_cli.cc b/modules/drivers/gnss/test/parser_cli.cc index 1954a98416f..daa60597326 100644 --- a/modules/drivers/gnss/test/parser_cli.cc +++ b/modules/drivers/gnss/test/parser_cli.cc @@ -23,8 +23,8 @@ #include #include -#include "cybertron/cybertron.h" -#include "cybertron/record/record_reader.h" +#include "cyber/cyber.h" +#include "cyber/record/record_reader.h" #include "modules/drivers/gnss/parser/data_parser.h" #include "modules/drivers/gnss/proto/config.pb.h" @@ -67,8 +67,8 @@ void ParseBag(const char* filename, DataParser* parser) { } void ParseRecord(const char* filename, DataParser* parser) { - cybertron::record::RecordReader reader(filename); - cybertron::record::RecordMessage message; + cyber::record::RecordReader reader(filename); + cyber::record::RecordMessage message; while (reader.ReadMessage(&message)) { if (message.channel_name == "/apollo/sensor/gnss/raw_data") { apollo::drivers::gnss::RawData msg; @@ -80,10 +80,10 @@ void ParseRecord(const char* filename, DataParser* parser) { } void Parse(const char* filename, const char* file_type, - const std::shared_ptr<::apollo::cybertron::Node>& node) { + const std::shared_ptr<::apollo::cyber::Node>& node) { std::string type = std::string(file_type); config::Config config; - if (!apollo::cybertron::common::GetProtoFromFile( + if (!apollo::cyber::common::GetProtoFromFile( std::string("/apollo/modules/drivers/gnss/conf/gnss_conf.pb.txt"), &config)) { std::cout << "Unable to load gnss conf file"; @@ -111,9 +111,9 @@ int main(int argc, char** argv) { std::cout << "Usage: " << argv[0] << " filename [record|bin]" << std::endl; return 0; } - ::apollo::cybertron::Init("parser_cli"); - std::shared_ptr<::apollo::cybertron::Node> parser_node( - ::apollo::cybertron::CreateNode("parser_cli")); + ::apollo::cyber::Init("parser_cli"); + std::shared_ptr<::apollo::cyber::Node> parser_node( + ::apollo::cyber::CreateNode("parser_cli")); ::apollo::drivers::gnss::Parse(argv[1], argv[2], parser_node); return 0; } diff --git a/modules/drivers/radar/conti_radar/BUILD b/modules/drivers/radar/conti_radar/BUILD index f236ee2b4f8..857b2179a82 100644 --- a/modules/drivers/radar/conti_radar/BUILD +++ b/modules/drivers/radar/conti_radar/BUILD @@ -39,7 +39,7 @@ cc_library( "//modules/localization/proto:pose_proto", "//modules/localization/proto:localization_proto", "@eigen//:eigen", - "//cybertron", + "//cyber", ], copts = ['-DMODULE_NAME=\\"conti_radar\\"'] ) diff --git a/modules/drivers/radar/conti_radar/conti_radar_canbus_component.cc b/modules/drivers/radar/conti_radar/conti_radar_canbus_component.cc index 5aa5d19733d..d47822b1cff 100644 --- a/modules/drivers/radar/conti_radar/conti_radar_canbus_component.cc +++ b/modules/drivers/radar/conti_radar/conti_radar_canbus_component.cc @@ -130,7 +130,7 @@ bool ContiRadarCanbusComponent::OnError(const std::string& error_msg) { void ContiRadarCanbusComponent::PoseCallback( const std::shared_ptr& pose_msg) { auto send_interval = conti_radar_conf_.radar_conf().input_send_interval(); - uint64_t now_nsec = cybertron::Time().Now().ToNanosecond(); + uint64_t now_nsec = cyber::Time().Now().ToNanosecond(); if (last_nsec_ != 0 && (now_nsec - last_nsec_) < send_interval) { return; } diff --git a/modules/drivers/radar/conti_radar/conti_radar_canbus_component.h b/modules/drivers/radar/conti_radar/conti_radar_canbus_component.h index 7865779fc70..9e4209ae813 100644 --- a/modules/drivers/radar/conti_radar/conti_radar_canbus_component.h +++ b/modules/drivers/radar/conti_radar/conti_radar_canbus_component.h @@ -25,7 +25,7 @@ #include #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/common/monitor_log/monitor_log_buffer.h" #include "modules/common/util/util.h" @@ -66,10 +66,10 @@ using apollo::drivers::canbus::CanReceiver; using apollo::drivers::canbus::SenderMessage; using apollo::drivers::canbus::SensorCanbusConf; using apollo::localization::LocalizationEstimate; -using apollo::cybertron::Writer; -using apollo::cybertron::Reader; +using apollo::cyber::Writer; +using apollo::cyber::Reader; -class ContiRadarCanbusComponent : public apollo::cybertron::Component<> { +class ContiRadarCanbusComponent : public apollo::cyber::Component<> { public: ContiRadarCanbusComponent(); ~ContiRadarCanbusComponent(); @@ -96,7 +96,7 @@ class ContiRadarCanbusComponent : public apollo::cybertron::Component<> { apollo::common::monitor::MonitorLogBuffer monitor_logger_buffer_; }; -CYBERTRON_REGISTER_COMPONENT(ContiRadarCanbusComponent) +CYBER_REGISTER_COMPONENT(ContiRadarCanbusComponent) } // namespace conti_radar } // namespace drivers diff --git a/modules/drivers/radar/conti_radar/conti_radar_message_manager.h b/modules/drivers/radar/conti_radar/conti_radar_message_manager.h index 1d114f1a509..37661e1f27b 100644 --- a/modules/drivers/radar/conti_radar/conti_radar_message_manager.h +++ b/modules/drivers/radar/conti_radar/conti_radar_message_manager.h @@ -21,7 +21,7 @@ #pragma once #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/drivers/canbus/can_client/can_client_factory.h" #include "modules/drivers/canbus/can_comm/can_sender.h" #include "modules/drivers/canbus/can_comm/message_manager.h" @@ -42,7 +42,7 @@ using apollo::drivers::canbus::CanClient; using apollo::drivers::canbus::SenderMessage; using apollo::drivers::conti_radar::RadarConfig200; template -using Writer = apollo::cybertron::Writer; +using Writer = apollo::cyber::Writer; class ContiRadarMessageManager : public MessageManager { public: diff --git a/modules/drivers/radar/conti_radar/launch/conti_radar.launch b/modules/drivers/radar/conti_radar/launch/conti_radar.launch index df2704149dd..8212d5a5000 100644 --- a/modules/drivers/radar/conti_radar/launch/conti_radar.launch +++ b/modules/drivers/radar/conti_radar/launch/conti_radar.launch @@ -1,7 +1,7 @@ - + conti_radar /apollo/modules/drivers/radar/conti_radar/dag/conti_radar.dag conti_radar - + diff --git a/modules/drivers/radar/racobit_radar/BUILD b/modules/drivers/radar/racobit_radar/BUILD index 34a2ec4a213..e54877f06f2 100644 --- a/modules/drivers/radar/racobit_radar/BUILD +++ b/modules/drivers/radar/racobit_radar/BUILD @@ -41,7 +41,7 @@ cc_library( ], deps = [ ":racobit_radar_message_manager", - "//cybertron", + "//cyber", "//modules/common", "//modules/common/adapters:adapter_gflags", "//modules/common/monitor_log", diff --git a/modules/drivers/radar/racobit_radar/launch/racobit_radar.launch b/modules/drivers/radar/racobit_radar/launch/racobit_radar.launch index 6e6217c2934..e7ce1edbfb7 100644 --- a/modules/drivers/radar/racobit_radar/launch/racobit_radar.launch +++ b/modules/drivers/radar/racobit_radar/launch/racobit_radar.launch @@ -1,7 +1,7 @@ - + racobit_radar /apollo/modules/drivers/radar/racobit_radar/dag/racobit_radar.dag - + diff --git a/modules/drivers/radar/racobit_radar/racobit_radar_canbus_component.h b/modules/drivers/radar/racobit_radar/racobit_radar_canbus_component.h index 73323f8676b..edcd4000dae 100644 --- a/modules/drivers/radar/racobit_radar/racobit_radar_canbus_component.h +++ b/modules/drivers/radar/racobit_radar/racobit_radar_canbus_component.h @@ -25,7 +25,7 @@ #include #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/common/monitor_log/monitor_log_buffer.h" #include "modules/common/time/time.h" @@ -68,7 +68,7 @@ using apollo::drivers::canbus::CanReceiver; using apollo::drivers::canbus::SenderMessage; using apollo::drivers::canbus::SensorCanbusConf; -class RacobitRadarCanbusComponent : public apollo::cybertron::Component<> { +class RacobitRadarCanbusComponent : public apollo::cyber::Component<> { public: // TODO(lizh): check whether we need a new msg item, say // MonitorMessageItem::SENSORCANBUS @@ -92,12 +92,12 @@ class RacobitRadarCanbusComponent : public apollo::cybertron::Component<> { int64_t last_timestamp_ = 0; apollo::common::monitor::MonitorLogBuffer monitor_logger_buffer_; bool start_success_ = false; - // cybertron + // cyber RacobitRadarConf racobit_radar_conf_; - std::shared_ptr> racobit_radar_writer_; + std::shared_ptr> racobit_radar_writer_; }; -CYBERTRON_REGISTER_COMPONENT(RacobitRadarCanbusComponent) +CYBER_REGISTER_COMPONENT(RacobitRadarCanbusComponent) } // namespace racobit_radar } // namespace drivers diff --git a/modules/drivers/radar/racobit_radar/racobit_radar_message_manager.cc b/modules/drivers/radar/racobit_radar/racobit_radar_message_manager.cc index dadc83f3039..4f06bd69745 100644 --- a/modules/drivers/radar/racobit_radar/racobit_radar_message_manager.cc +++ b/modules/drivers/radar/racobit_radar/racobit_radar_message_manager.cc @@ -38,7 +38,7 @@ namespace drivers { namespace racobit_radar { RacobitRadarMessageManager::RacobitRadarMessageManager( - std::shared_ptr> writer) + std::shared_ptr> writer) : writer_(std::move(writer)) { AddRecvProtocolData(); AddRecvProtocolData(); diff --git a/modules/drivers/radar/racobit_radar/racobit_radar_message_manager.h b/modules/drivers/radar/racobit_radar/racobit_radar_message_manager.h index 4ba37091e7d..384b43d6959 100644 --- a/modules/drivers/radar/racobit_radar/racobit_radar_message_manager.h +++ b/modules/drivers/radar/racobit_radar/racobit_radar_message_manager.h @@ -22,7 +22,7 @@ #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/drivers/canbus/can_client/can_client_factory.h" #include "modules/drivers/canbus/can_comm/can_sender.h" @@ -48,7 +48,7 @@ using apollo::drivers::racobit_radar::RadarConfig200; class RacobitRadarMessageManager : public MessageManager { public: RacobitRadarMessageManager( - std::shared_ptr> writer); + std::shared_ptr> writer); virtual ~RacobitRadarMessageManager() {} void set_radar_conf(RadarConf radar_conf); ProtocolData *GetMutableProtocolDataById( @@ -60,7 +60,7 @@ class RacobitRadarMessageManager : public MessageManager { bool is_configured_ = false; RadarConfig200 radar_config_; std::shared_ptr can_client_; - std::shared_ptr> writer_; + std::shared_ptr> writer_; }; } // namespace racobit_radar diff --git a/modules/drivers/radar/ultrasonic_radar/launch/ultrasonic_radar.launch b/modules/drivers/radar/ultrasonic_radar/launch/ultrasonic_radar.launch index 5c4d227fd03..fd624587075 100644 --- a/modules/drivers/radar/ultrasonic_radar/launch/ultrasonic_radar.launch +++ b/modules/drivers/radar/ultrasonic_radar/launch/ultrasonic_radar.launch @@ -1,7 +1,7 @@ - + ultrasonic_radar /apollo/modules/drivers/radar/ultrasonic_radar/dag/ultrasonic_radar.dag - + diff --git a/modules/drivers/radar/ultrasonic_radar/ultrasonic_radar_canbus.cc b/modules/drivers/radar/ultrasonic_radar/ultrasonic_radar_canbus.cc index 2dec865ed36..695592d2fb8 100644 --- a/modules/drivers/radar/ultrasonic_radar/ultrasonic_radar_canbus.cc +++ b/modules/drivers/radar/ultrasonic_radar/ultrasonic_radar_canbus.cc @@ -43,7 +43,7 @@ std::string UltrasonicRadarCanbus::Name() const { apollo::common::Status UltrasonicRadarCanbus::Init( const std::string& config_path, - const std::shared_ptr<::apollo::cybertron::Writer>& writer) { + const std::shared_ptr<::apollo::cyber::Writer>& writer) { if (!apollo::common::util::GetProtoFromFile(config_path, &ultrasonic_radar_conf_)) { return OnError("Unable to load canbus conf file: " + config_path); diff --git a/modules/drivers/radar/ultrasonic_radar/ultrasonic_radar_canbus.h b/modules/drivers/radar/ultrasonic_radar/ultrasonic_radar_canbus.h index 555b5dc89e3..d5f11fa2d6c 100644 --- a/modules/drivers/radar/ultrasonic_radar/ultrasonic_radar_canbus.h +++ b/modules/drivers/radar/ultrasonic_radar/ultrasonic_radar_canbus.h @@ -25,7 +25,7 @@ #include #include -#include "cybertron/common/macros.h" +#include "cyber/common/macros.h" #include "modules/common/monitor_log/monitor_log_buffer.h" #include "modules/common/time/time.h" @@ -83,7 +83,7 @@ class UltrasonicRadarCanbus { */ apollo::common::Status Init( const std::string& config_path, - const std::shared_ptr<::apollo::cybertron::Writer>& writer); + const std::shared_ptr<::apollo::cyber::Writer>& writer); /** * @brief module start function diff --git a/modules/drivers/radar/ultrasonic_radar/ultrasonic_radar_canbus_component.h b/modules/drivers/radar/ultrasonic_radar/ultrasonic_radar_canbus_component.h index f9691d32dda..8285a7a2d48 100644 --- a/modules/drivers/radar/ultrasonic_radar/ultrasonic_radar_canbus_component.h +++ b/modules/drivers/radar/ultrasonic_radar/ultrasonic_radar_canbus_component.h @@ -28,17 +28,17 @@ namespace apollo { namespace drivers { namespace ultrasonic_radar { -class UltrasonicRadarCanbusComponent : public apollo::cybertron::Component<> { +class UltrasonicRadarCanbusComponent : public apollo::cyber::Component<> { public: UltrasonicRadarCanbusComponent(); ~UltrasonicRadarCanbusComponent() = default; bool Init() override; private: UltrasonicRadarCanbus utralsonic_radar_canbus_; - std::shared_ptr<::apollo::cybertron::Writer> writer_; + std::shared_ptr<::apollo::cyber::Writer> writer_; }; -CYBERTRON_REGISTER_COMPONENT(UltrasonicRadarCanbusComponent) +CYBER_REGISTER_COMPONENT(UltrasonicRadarCanbusComponent) } // namespace ultrasonic_radar } // namespace drivers diff --git a/modules/drivers/radar/ultrasonic_radar/ultrasonic_radar_message_manager.cc b/modules/drivers/radar/ultrasonic_radar/ultrasonic_radar_message_manager.cc index 58ab8973696..e7fc32c14fc 100644 --- a/modules/drivers/radar/ultrasonic_radar/ultrasonic_radar_message_manager.cc +++ b/modules/drivers/radar/ultrasonic_radar/ultrasonic_radar_message_manager.cc @@ -28,7 +28,7 @@ namespace ultrasonic_radar { UltrasonicRadarMessageManager::UltrasonicRadarMessageManager( const int entrance_num, - const std::shared_ptr<::apollo::cybertron::Writer> &writer) + const std::shared_ptr<::apollo::cyber::Writer> &writer) : entrance_num_(entrance_num), ultrasonic_radar_writer_(writer) { sensor_data_.mutable_ranges()->Resize(entrance_num_, 0.0); } diff --git a/modules/drivers/radar/ultrasonic_radar/ultrasonic_radar_message_manager.h b/modules/drivers/radar/ultrasonic_radar/ultrasonic_radar_message_manager.h index 9748fc8eca9..e2a9393b430 100644 --- a/modules/drivers/radar/ultrasonic_radar/ultrasonic_radar_message_manager.h +++ b/modules/drivers/radar/ultrasonic_radar/ultrasonic_radar_message_manager.h @@ -22,7 +22,7 @@ #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/drivers/canbus/can_client/can_client_factory.h" #include "modules/drivers/canbus/can_comm/can_sender.h" @@ -46,14 +46,14 @@ using apollo::drivers::canbus::SenderMessage; class UltrasonicRadarMessageManager : public MessageManager { public: explicit UltrasonicRadarMessageManager(const int entrance_num, - const std::shared_ptr<::apollo::cybertron::Writer> &writer); + const std::shared_ptr<::apollo::cyber::Writer> &writer); virtual ~UltrasonicRadarMessageManager() = default; void Parse(const uint32_t message_id, const uint8_t *data, int32_t length); void set_can_client(std::shared_ptr can_client); private: int entrance_num_ = 0; - std::shared_ptr> ultrasonic_radar_writer_; + std::shared_ptr> ultrasonic_radar_writer_; std::shared_ptr can_client_; }; diff --git a/modules/drivers/velodyne/compensator/BUILD b/modules/drivers/velodyne/compensator/BUILD index 85882453396..5d18da98473 100644 --- a/modules/drivers/velodyne/compensator/BUILD +++ b/modules/drivers/velodyne/compensator/BUILD @@ -15,7 +15,7 @@ cc_library( hdrs = ["compensator_component.h"], deps = [ "//modules/drivers/velodyne/compensator:compensator_lib", - "//cybertron", + "//cyber", ], copts = ['-DMODULE_NAME=\\"velodyne\\"'] ) @@ -32,7 +32,7 @@ cc_library( "//modules/drivers/velodyne/proto:velodyne_proto", "//modules/drivers/proto:sensor_proto", "//modules/transform:tf2_buffer_lib", - "//cybertron", + "//cyber", "@eigen", ], copts = ['-DMODULE_NAME=\\"velodyne\\"'] diff --git a/modules/drivers/velodyne/compensator/compensator.cc b/modules/drivers/velodyne/compensator/compensator.cc index 89f5c97322c..ea202d627b9 100644 --- a/modules/drivers/velodyne/compensator/compensator.cc +++ b/modules/drivers/velodyne/compensator/compensator.cc @@ -26,7 +26,7 @@ namespace velodyne { bool Compensator::QueryPoseAffineFromTF2(const uint64_t& timestamp, void* pose, const std::string& child_frame_id) { - cybertron::Time query_time(timestamp); + cyber::Time query_time(timestamp); std::string err_string; if (!tf2_buffer_ptr_->canTransform( config_.world_frame_id(), child_frame_id, query_time, @@ -61,7 +61,7 @@ bool Compensator::QueryPoseAffineFromTF2(const uint64_t& timestamp, void* pose, bool Compensator::MotionCompensation( const std::shared_ptr& msg, std::shared_ptr msg_compensated) { - uint64_t start = cybertron::Time::Now().ToNanosecond(); + uint64_t start = cyber::Time::Now().ToNanosecond(); Eigen::Affine3d pose_min_time; Eigen::Affine3d pose_max_time; @@ -71,7 +71,7 @@ bool Compensator::MotionCompensation( GetTimestampInterval(msg, ×tamp_min, ×tamp_max); msg_compensated->mutable_header()->set_timestamp_sec( - cybertron::Time::Now().ToSecond()); + cyber::Time::Now().ToSecond()); msg_compensated->mutable_header()->set_frame_id(msg->header().frame_id()); msg_compensated->mutable_header()->set_lidar_timestamp( msg->header().lidar_timestamp()); @@ -79,7 +79,7 @@ bool Compensator::MotionCompensation( msg_compensated->set_height(msg->height()); msg_compensated->set_is_dense(msg->is_dense()); - uint64_t new_time = cybertron::Time().Now().ToNanosecond(); + uint64_t new_time = cyber::Time().Now().ToNanosecond(); AINFO << "compenstator new msg diff:" << new_time - start << ";meta:" << msg->header().lidar_timestamp(); msg_compensated->mutable_point()->Reserve(240000); @@ -87,12 +87,12 @@ bool Compensator::MotionCompensation( // compensate point cloud, remove nan point if (QueryPoseAffineFromTF2(timestamp_min, &pose_min_time, frame_id) && QueryPoseAffineFromTF2(timestamp_max, &pose_max_time, frame_id)) { - uint64_t tf_time = cybertron::Time().Now().ToNanosecond(); + uint64_t tf_time = cyber::Time().Now().ToNanosecond(); AINFO << "compenstator tf msg diff:" << tf_time - new_time << ";meta:" << msg->header().lidar_timestamp(); MotionCompensation(msg, msg_compensated, timestamp_min, timestamp_max, pose_min_time, pose_max_time); - uint64_t com_time = cybertron::Time().Now().ToNanosecond(); + uint64_t com_time = cyber::Time().Now().ToNanosecond(); msg_compensated->set_width(msg_compensated->point_size() / msg->height()); AINFO << "compenstator com msg diff:" << com_time - tf_time diff --git a/modules/drivers/velodyne/compensator/compensator_component.cc b/modules/drivers/velodyne/compensator/compensator_component.cc index b0d0b872d6e..578f9993361 100644 --- a/modules/drivers/velodyne/compensator/compensator_component.cc +++ b/modules/drivers/velodyne/compensator/compensator_component.cc @@ -47,7 +47,7 @@ bool CompensatorComponent::Init() { bool CompensatorComponent::Proc( const std::shared_ptr& point_cloud) { - uint64_t start = cybertron::Time().Now().ToNanosecond(); + uint64_t start = cyber::Time().Now().ToNanosecond(); if (index_ >= queue_size_) { index_ = 0; } @@ -55,7 +55,7 @@ bool CompensatorComponent::Proc( compensator_deque_[index_++]; point_cloud_compensated->Clear(); if (compensator_->MotionCompensation(point_cloud, point_cloud_compensated)) { - uint64_t diff = cybertron::Time().Now().ToNanosecond() - start; + uint64_t diff = cyber::Time().Now().ToNanosecond() - start; AINFO << "compenstator diff:" << diff << ";meta:" << point_cloud_compensated->header().lidar_timestamp(); point_cloud_compensated->mutable_header()->set_sequence_num(seq_); diff --git a/modules/drivers/velodyne/compensator/compensator_component.h b/modules/drivers/velodyne/compensator/compensator_component.h index 0d64523da46..2c44789f28a 100644 --- a/modules/drivers/velodyne/compensator/compensator_component.h +++ b/modules/drivers/velodyne/compensator/compensator_component.h @@ -19,7 +19,7 @@ #include #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/drivers/proto/pointcloud.pb.h" #include "modules/drivers/velodyne/compensator/compensator.h" @@ -28,9 +28,9 @@ namespace apollo { namespace drivers { namespace velodyne { -using apollo::cybertron::Component; -using apollo::cybertron::Reader; -using apollo::cybertron::Writer; +using apollo::cyber::Component; +using apollo::cyber::Reader; +using apollo::cyber::Writer; using apollo::drivers::PointCloud; class CompensatorComponent : public Component { @@ -47,7 +47,7 @@ class CompensatorComponent : public Component { std::shared_ptr> writer_ = nullptr; }; -CYBERTRON_REGISTER_COMPONENT(CompensatorComponent) +CYBER_REGISTER_COMPONENT(CompensatorComponent) } // namespace velodyne } // namespace drivers } // namespace apollo diff --git a/modules/drivers/velodyne/driver/BUILD b/modules/drivers/velodyne/driver/BUILD index 1b6ad91ec22..97b93fe091a 100644 --- a/modules/drivers/velodyne/driver/BUILD +++ b/modules/drivers/velodyne/driver/BUILD @@ -16,7 +16,7 @@ cc_library( deps = [ "//modules/drivers/velodyne/driver:driver", "//modules/common/util:message_util", - "//cybertron", + "//cyber", ], copts = ['-DMODULE_NAME=\\"velodyne\\"'] ) @@ -40,7 +40,7 @@ cc_library( deps = [ "//modules/common/util", "//modules/drivers/velodyne/proto:velodyne_proto", - "//cybertron", + "//cyber", "@pcl", ], copts = ['-DMODULE_NAME=\\"velodyne\\"'] diff --git a/modules/drivers/velodyne/driver/driver.cc b/modules/drivers/velodyne/driver/driver.cc index 7361ac9ddec..06f9355d85c 100644 --- a/modules/drivers/velodyne/driver/driver.cc +++ b/modules/drivers/velodyne/driver/driver.cc @@ -18,7 +18,7 @@ #include #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/drivers/velodyne/driver/driver.h" #include "modules/drivers/velodyne/proto/config.pb.h" @@ -118,7 +118,7 @@ bool VelodyneDriver::Poll(const std::shared_ptr& scan) { // publish message using time of last packet read ADEBUG << "Publishing a full Velodyne scan."; - scan->mutable_header()->set_timestamp_sec(cybertron::Time().Now().ToSecond()); + scan->mutable_header()->set_timestamp_sec(cyber::Time().Now().ToSecond()); scan->mutable_header()->set_frame_id(config_.frame_id()); scan->set_model(config_.model()); scan->set_mode(config_.mode()); @@ -165,7 +165,7 @@ int VelodyneDriver::PollStandard(std::shared_ptr scan) { } void VelodyneDriver::PollPositioningPacket(void) { - while (!cybertron::IsShutdown()) { + while (!cyber::IsShutdown()) { NMEATimePtr nmea_time(new NMEATime); bool ret = true; if (config_.has_use_gps_time() && !config_.use_gps_time()) { @@ -183,7 +183,7 @@ void VelodyneDriver::PollPositioningPacket(void) { << "day:" << nmea_time->day << "hour:" << nmea_time->hour << "min:" << nmea_time->min << "sec:" << nmea_time->sec; } else { - while (!cybertron::IsShutdown()) { + while (!cyber::IsShutdown()) { int rc = positioning_input_->get_positioning_data_packet(nmea_time); if (rc == 0) { break; // got a full packet diff --git a/modules/drivers/velodyne/driver/driver64.cc b/modules/drivers/velodyne/driver/driver64.cc index 642973e6ba3..fc58850d18a 100644 --- a/modules/drivers/velodyne/driver/driver64.cc +++ b/modules/drivers/velodyne/driver/driver64.cc @@ -57,7 +57,7 @@ bool Velodyne64Driver::Poll(const std::shared_ptr& scan) { // publish message using time of last packet read ADEBUG << "Publishing a full Velodyne scan."; - scan->mutable_header()->set_timestamp_sec(cybertron::Time().Now().ToSecond()); + scan->mutable_header()->set_timestamp_sec(cyber::Time().Now().ToSecond()); scan->mutable_header()->set_frame_id(config_.frame_id()); scan->set_model(config_.model()); scan->set_mode(config_.mode()); diff --git a/modules/drivers/velodyne/driver/input.h b/modules/drivers/velodyne/driver/input.h index e29a7a71529..0520759532d 100644 --- a/modules/drivers/velodyne/driver/input.h +++ b/modules/drivers/velodyne/driver/input.h @@ -19,7 +19,7 @@ #include #include #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" // #include "velodyne_msgs/VelodyneScanUnified.h" #include "modules/drivers/velodyne/proto/velodyne.pb.h" diff --git a/modules/drivers/velodyne/driver/socket_input.cc b/modules/drivers/velodyne/driver/socket_input.cc index 3657d80d4fd..c3b5d560fbd 100644 --- a/modules/drivers/velodyne/driver/socket_input.cc +++ b/modules/drivers/velodyne/driver/socket_input.cc @@ -92,7 +92,7 @@ void SocketInput::init(const int &port) { /** @brief Get one velodyne packet. */ int SocketInput::get_firing_data_packet(VelodynePacket *pkt) { // double time1 = ros::Time::now().toSec(); - double time1 = apollo::cybertron::Time().Now().ToSecond(); + double time1 = apollo::cyber::Time().Now().ToSecond(); while (true) { if (!input_available(POLL_TIMEOUT)) { return SOCKET_TIMEOUT; @@ -119,8 +119,8 @@ int SocketInput::get_firing_data_packet(VelodynePacket *pkt) { AERROR << "Incomplete Velodyne rising data packet read: " << nbytes << " bytes from port " << port_; } - double time2 = apollo::cybertron::Time().Now().ToSecond(); - pkt->set_stamp(apollo::cybertron::Time((time2 + time1) / 2.0).ToNanosecond()); + double time2 = apollo::cyber::Time().Now().ToSecond(); + pkt->set_stamp(apollo::cyber::Time((time2 + time1) / 2.0).ToNanosecond()); return 0; } diff --git a/modules/drivers/velodyne/driver/velodyne_driver_component.cc b/modules/drivers/velodyne/driver/velodyne_driver_component.cc index b85d439b0f7..bfd2c6a662b 100644 --- a/modules/drivers/velodyne/driver/velodyne_driver_component.cc +++ b/modules/drivers/velodyne/driver/velodyne_driver_component.cc @@ -18,7 +18,7 @@ #include #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/common/util/message_util.h" #include "modules/drivers/velodyne/driver/velodyne_driver_component.h" @@ -53,7 +53,7 @@ bool VelodyneDriverComponent::Init() { /** @brief Device poll thread main loop. */ void VelodyneDriverComponent::device_poll() { - while (!apollo::cybertron::IsShutdown()) { + while (!apollo::cyber::IsShutdown()) { // poll device until end of file std::shared_ptr scan = std::make_shared(); bool ret = dvr_->Poll(scan); diff --git a/modules/drivers/velodyne/driver/velodyne_driver_component.h b/modules/drivers/velodyne/driver/velodyne_driver_component.h index 697a2c02339..037ad29bb71 100644 --- a/modules/drivers/velodyne/driver/velodyne_driver_component.h +++ b/modules/drivers/velodyne/driver/velodyne_driver_component.h @@ -19,7 +19,7 @@ #include #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/drivers/velodyne/driver/driver.h" #include "modules/drivers/velodyne/proto/config.pb.h" @@ -29,9 +29,9 @@ namespace apollo { namespace drivers { namespace velodyne { -using apollo::cybertron::Component; -using apollo::cybertron::Reader; -using apollo::cybertron::Writer; +using apollo::cyber::Component; +using apollo::cyber::Reader; +using apollo::cyber::Writer; using apollo::drivers::velodyne::VelodyneScan; class VelodyneDriverComponent : public Component<> { @@ -49,10 +49,10 @@ class VelodyneDriverComponent : public Component<> { uint32_t seq_ = 0; std::shared_ptr device_thread_; std::shared_ptr dvr_; ///< driver implementation class - std::shared_ptr> writer_; + std::shared_ptr> writer_; }; -CYBERTRON_REGISTER_COMPONENT(VelodyneDriverComponent) +CYBER_REGISTER_COMPONENT(VelodyneDriverComponent) } // namespace velodyne } // namespace drivers diff --git a/modules/drivers/velodyne/fusion/BUILD b/modules/drivers/velodyne/fusion/BUILD index 5fb85eefe00..3e0329acb14 100644 --- a/modules/drivers/velodyne/fusion/BUILD +++ b/modules/drivers/velodyne/fusion/BUILD @@ -14,7 +14,7 @@ cc_library( srcs = ["pri_sec_fusion_component.cc"], hdrs = ["pri_sec_fusion_component.h"], deps = [ - "//cybertron", + "//cyber", "//modules/drivers/velodyne/proto:velodyne_proto", "//modules/drivers/proto:sensor_proto", "//modules/transform:tf2_buffer_lib", diff --git a/modules/drivers/velodyne/fusion/pri_sec_fusion_component.cc b/modules/drivers/velodyne/fusion/pri_sec_fusion_component.cc index 304b70335cd..ddba5ced9ff 100644 --- a/modules/drivers/velodyne/fusion/pri_sec_fusion_component.cc +++ b/modules/drivers/velodyne/fusion/pri_sec_fusion_component.cc @@ -22,7 +22,7 @@ namespace apollo { namespace drivers { namespace velodyne { -using apollo::cybertron::Time; +using apollo::cyber::Time; bool PriSecFusionComponent::Init() { if (!GetProtoConfig(&conf_)) { @@ -81,7 +81,7 @@ bool PriSecFusionComponent::QueryPoseAffine(const std::string& target_frame_id, Eigen::Affine3d* pose) { std::string err_string; if (!buffer_ptr_->canTransform(target_frame_id, source_frame_id, - cybertron::Time(0), 0.02, &err_string)) { + cyber::Time(0), 0.02, &err_string)) { AERROR << "Can not find transform. " << "target_id:" << target_frame_id << " frame_id:" << source_frame_id << " Error info: " << err_string; @@ -90,7 +90,7 @@ bool PriSecFusionComponent::QueryPoseAffine(const std::string& target_frame_id, apollo::transform::TransformStamped stamped_transform; try { stamped_transform = buffer_ptr_->lookupTransform( - target_frame_id, source_frame_id, cybertron::Time(0)); + target_frame_id, source_frame_id, cyber::Time(0)); } catch (tf2::TransformException& ex) { AERROR << ex.what(); return false; diff --git a/modules/drivers/velodyne/fusion/pri_sec_fusion_component.h b/modules/drivers/velodyne/fusion/pri_sec_fusion_component.h index 3456d27f0d1..bc7482bb879 100644 --- a/modules/drivers/velodyne/fusion/pri_sec_fusion_component.h +++ b/modules/drivers/velodyne/fusion/pri_sec_fusion_component.h @@ -21,7 +21,7 @@ #include #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/drivers/proto/pointcloud.pb.h" #include "modules/drivers/velodyne/proto/config.pb.h" @@ -31,9 +31,9 @@ namespace apollo { namespace drivers { namespace velodyne { -using apollo::cybertron::Component; -using apollo::cybertron::Reader; -using apollo::cybertron::Writer; +using apollo::cyber::Component; +using apollo::cyber::Reader; +using apollo::cyber::Writer; using apollo::drivers::PointCloud; class PriSecFusionComponent : public Component { @@ -60,7 +60,7 @@ class PriSecFusionComponent : public Component { std::vector>> readers_; }; -CYBERTRON_REGISTER_COMPONENT(PriSecFusionComponent) +CYBER_REGISTER_COMPONENT(PriSecFusionComponent) } // namespace velodyne } // namespace drivers } // namespace apollo diff --git a/modules/drivers/velodyne/launch/velodyne.launch b/modules/drivers/velodyne/launch/velodyne.launch index 01391bd639e..a2a652ff791 100644 --- a/modules/drivers/velodyne/launch/velodyne.launch +++ b/modules/drivers/velodyne/launch/velodyne.launch @@ -1,7 +1,7 @@ - + velodyne /apollo/modules/drivers/velodyne/dag/velodyne.dag velodyne - + diff --git a/modules/drivers/velodyne/launch/velodyne128.launch b/modules/drivers/velodyne/launch/velodyne128.launch index e0a212e03b0..142e6f01a91 100644 --- a/modules/drivers/velodyne/launch/velodyne128.launch +++ b/modules/drivers/velodyne/launch/velodyne128.launch @@ -1,7 +1,7 @@ - + gnss /apollo/modules/drivers/velodyne/dag/velodyne128.dag gnss - + diff --git a/modules/drivers/velodyne/parser/BUILD b/modules/drivers/velodyne/parser/BUILD index af84e4defd6..466e5cfb9ab 100644 --- a/modules/drivers/velodyne/parser/BUILD +++ b/modules/drivers/velodyne/parser/BUILD @@ -15,7 +15,7 @@ cc_library( hdrs = ["velodyne_convert_component.h"], deps = [ "//modules/drivers/velodyne/parser:convert", - "//cybertron", + "//cyber", ], copts = ['-DMODULE_NAME=\\"velodyne\\"'] ) @@ -44,7 +44,7 @@ cc_library( deps = [ "//modules/drivers/velodyne/proto:velodyne_proto", "//modules/drivers/proto:sensor_proto", - "//cybertron", + "//cyber", "@eigen", "@yaml_cpp//:yaml", ], diff --git a/modules/drivers/velodyne/parser/online_calibration.h b/modules/drivers/velodyne/parser/online_calibration.h index 33c5e660c12..eb451fc84a4 100644 --- a/modules/drivers/velodyne/parser/online_calibration.h +++ b/modules/drivers/velodyne/parser/online_calibration.h @@ -20,7 +20,7 @@ #include #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/drivers/velodyne/parser/calibration.h" #include "modules/drivers/velodyne/proto/velodyne.pb.h" diff --git a/modules/drivers/velodyne/parser/velodyne128_parser.cc b/modules/drivers/velodyne/parser/velodyne128_parser.cc index b9fcb68da15..81d39ea5fec 100644 --- a/modules/drivers/velodyne/parser/velodyne128_parser.cc +++ b/modules/drivers/velodyne/parser/velodyne128_parser.cc @@ -32,7 +32,7 @@ void Velodyne128Parser::GeneratePointcloud( // allocate a point cloud with same time and frame ID as raw data out_msg->mutable_header()->set_frame_id(scan_msg->header().frame_id()); out_msg->mutable_header()->set_timestamp_sec( - cybertron::Time().Now().ToSecond()); + cyber::Time().Now().ToSecond()); out_msg->set_height(1); // us diff --git a/modules/drivers/velodyne/parser/velodyne_convert_component.cc b/modules/drivers/velodyne/parser/velodyne_convert_component.cc index ea3005a8de7..5df7ae7f2f6 100644 --- a/modules/drivers/velodyne/parser/velodyne_convert_component.cc +++ b/modules/drivers/velodyne/parser/velodyne_convert_component.cc @@ -18,7 +18,7 @@ #include #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/drivers/velodyne/parser/velodyne_convert_component.h" diff --git a/modules/drivers/velodyne/parser/velodyne_convert_component.h b/modules/drivers/velodyne/parser/velodyne_convert_component.h index 903e265f49b..7f2d4b6dd53 100644 --- a/modules/drivers/velodyne/parser/velodyne_convert_component.h +++ b/modules/drivers/velodyne/parser/velodyne_convert_component.h @@ -21,7 +21,7 @@ #include #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/drivers/velodyne/parser/convert.h" #include "modules/drivers/velodyne/proto/config.pb.h" @@ -31,9 +31,9 @@ namespace apollo { namespace drivers { namespace velodyne { -using apollo::cybertron::Component; -using apollo::cybertron::Reader; -using apollo::cybertron::Writer; +using apollo::cyber::Component; +using apollo::cyber::Reader; +using apollo::cyber::Writer; using apollo::drivers::PointCloud; using apollo::drivers::velodyne::VelodyneScan; @@ -50,7 +50,7 @@ class VelodyneConvertComponent : public Component { int index_ = 0; }; -CYBERTRON_REGISTER_COMPONENT(VelodyneConvertComponent) +CYBER_REGISTER_COMPONENT(VelodyneConvertComponent) } // namespace velodyne } // namespace drivers diff --git a/modules/drivers/velodyne/parser/velodyne_parser.cc b/modules/drivers/velodyne/parser/velodyne_parser.cc index 1c9763c1837..d1c7bcecfbf 100644 --- a/modules/drivers/velodyne/parser/velodyne_parser.cc +++ b/modules/drivers/velodyne/parser/velodyne_parser.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/drivers/velodyne/parser/util.h" #include "modules/drivers/velodyne/parser/velodyne_parser.h" diff --git a/modules/guardian/BUILD b/modules/guardian/BUILD index 9ee45459e01..212f3a009b8 100644 --- a/modules/guardian/BUILD +++ b/modules/guardian/BUILD @@ -16,7 +16,7 @@ cc_binary( "//modules/monitor/proto:system_status_proto", "//modules/guardian/proto:guardian_proto", "//modules/guardian/proto:guardian_conf_proto", - "//cybertron", + "//cyber", ], copts = ['-DMODULE_NAME=\\"guardian\\"'], linkshared = True, diff --git a/modules/guardian/guardian_component.cc b/modules/guardian/guardian_component.cc index 48c95f05aab..7be3da4d07a 100644 --- a/modules/guardian/guardian_component.cc +++ b/modules/guardian/guardian_component.cc @@ -17,7 +17,7 @@ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/adapters/adapter_gflags.h" #include "modules/common/util/message_util.h" @@ -27,8 +27,8 @@ namespace guardian { using apollo::canbus::Chassis; using apollo::common::ErrorCode; using apollo::control::ControlCommand; -using apollo::cybertron::Reader; -using apollo::cybertron::Writer; +using apollo::cyber::Reader; +using apollo::cyber::Writer; using apollo::monitor::SystemStatus; bool GuardianComponent::Init() { diff --git a/modules/guardian/guardian_component.h b/modules/guardian/guardian_component.h index 390446f3f8e..47f37e2f06f 100644 --- a/modules/guardian/guardian_component.h +++ b/modules/guardian/guardian_component.h @@ -26,9 +26,9 @@ #include #include -#include "cybertron/common/macros.h" -#include "cybertron/component/timer_component.h" -#include "cybertron/cybertron.h" +#include "cyber/common/macros.h" +#include "cyber/component/timer_component.h" +#include "cyber/cyber.h" #include "modules/canbus/proto/chassis.pb.h" #include "modules/control/proto/control_cmd.pb.h" @@ -43,7 +43,7 @@ namespace apollo { namespace guardian { -class GuardianComponent : public apollo::cybertron::TimerComponent { +class GuardianComponent : public apollo::cyber::TimerComponent { public: bool Init() override; bool Proc() override; @@ -58,19 +58,19 @@ class GuardianComponent : public apollo::cybertron::TimerComponent { apollo::control::ControlCommand control_cmd_; apollo::guardian::GuardianCommand guardian_cmd_; - std::shared_ptr> + std::shared_ptr> chassis_reader_; - std::shared_ptr> + std::shared_ptr> control_cmd_reader_; - std::shared_ptr> + std::shared_ptr> system_status_reader_; - std::shared_ptr> + std::shared_ptr> guardian_writer_; std::mutex mutex_; }; -CYBERTRON_REGISTER_COMPONENT(GuardianComponent) +CYBER_REGISTER_COMPONENT(GuardianComponent) } // namespace guardian } // namespace apollo diff --git a/modules/guardian/launch/guardian.launch b/modules/guardian/launch/guardian.launch index fbc56a17dde..3cefbbac454 100644 --- a/modules/guardian/launch/guardian.launch +++ b/modules/guardian/launch/guardian.launch @@ -1,7 +1,7 @@ - + guardian /apollo/modules/guardian/dag/guardian.dag guardian - + diff --git a/modules/localization/common/BUILD b/modules/localization/common/BUILD index 5a3281c8953..4956c77c711 100644 --- a/modules/localization/common/BUILD +++ b/modules/localization/common/BUILD @@ -11,7 +11,7 @@ cc_library( "*.h", ]), deps = [ - "//cybertron", + "//cyber", "//modules/dreamview/backend/hmi:vehicle_manager", "//modules/localization/proto:localization_proto", ], diff --git a/modules/localization/launch/localization.launch b/modules/localization/launch/localization.launch index d923244f0f1..8bc8a511c05 100644 --- a/modules/localization/launch/localization.launch +++ b/modules/localization/launch/localization.launch @@ -1,7 +1,7 @@ - + localization /apollo/modules/localization/dag/localization.dag localization - + diff --git a/modules/localization/launch/msf_localization.launch b/modules/localization/launch/msf_localization.launch index 65ecffe5da6..722442afebe 100644 --- a/modules/localization/launch/msf_localization.launch +++ b/modules/localization/launch/msf_localization.launch @@ -1,7 +1,7 @@ - + localization /apollo/modules/localization/dag/dag_streaming_msf_localization.dag localization - + diff --git a/modules/localization/launch/msf_localization_with_visualizer.launch b/modules/localization/launch/msf_localization_with_visualizer.launch index 85793a879e1..0274dca0162 100644 --- a/modules/localization/launch/msf_localization_with_visualizer.launch +++ b/modules/localization/launch/msf_localization_with_visualizer.launch @@ -1,4 +1,4 @@ - + localization /apollo/modules/localization/dag/dag_streaming_msf_localization.dag @@ -9,4 +9,4 @@ /apollo/modules/localization/dag/dag_streaming_msf_visualizer.dag localization_visualizer - + diff --git a/modules/localization/launch/msf_visualizer.launch b/modules/localization/launch/msf_visualizer.launch index e5e6e675fe1..14469e94e97 100644 --- a/modules/localization/launch/msf_visualizer.launch +++ b/modules/localization/launch/msf_visualizer.launch @@ -1,7 +1,7 @@ - + localization_visualizer /apollo/modules/localization/dag/dag_streaming_msf_visualizer.dag localization_visualizer - + diff --git a/modules/localization/launch/rtk_localization.launch b/modules/localization/launch/rtk_localization.launch index 1e2b2e5af2c..8b6dd2269b4 100644 --- a/modules/localization/launch/rtk_localization.launch +++ b/modules/localization/launch/rtk_localization.launch @@ -1,7 +1,7 @@ - + localization /apollo/modules/localization/dag/dag_streaming_rtk_localization.dag localization - + diff --git a/modules/localization/localization.cc b/modules/localization/localization.cc index 05082c54613..7f6b3bb62d2 100644 --- a/modules/localization/localization.cc +++ b/modules/localization/localization.cc @@ -16,7 +16,7 @@ #include "modules/localization/localization.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/file.h" #include "modules/localization/common/localization_gflags.h" #ifdef __x86_64__ diff --git a/modules/localization/msf/BUILD b/modules/localization/msf/BUILD index 39bc367529f..74912b67443 100644 --- a/modules/localization/msf/BUILD +++ b/modules/localization/msf/BUILD @@ -43,7 +43,7 @@ cc_library( "//modules/localization/proto:sins_pva_proto", "//modules/localization/proto:msf_config_proto", "//modules/transform:transform_broadcaster_lib", - "//cybertron", + "//cyber", "@glog", "@gtest", "@yaml_cpp//:yaml", @@ -67,7 +67,7 @@ cc_binary( # data = ["//modules/localization:localization_testdata"], # deps = [ # ":msf_localization", -# "//cybertron", +# "//cyber", # "//modules/common/time", # "//modules/common/util", # "@gtest//:main", diff --git a/modules/localization/msf/common/io/BUILD b/modules/localization/msf/common/io/BUILD index 1396fe92698..6da5d5ba009 100644 --- a/modules/localization/msf/common/io/BUILD +++ b/modules/localization/msf/common/io/BUILD @@ -7,7 +7,7 @@ cc_library( srcs = glob(["*.cc"]), hdrs = glob(["*.h"]), deps = [ - "//cybertron", + "//cyber", "@eigen", "@pcl", "@yaml_cpp//:yaml", diff --git a/modules/localization/msf/common/io/velodyne_utility.cc b/modules/localization/msf/common/io/velodyne_utility.cc index 643c6aff858..cfda595b54e 100755 --- a/modules/localization/msf/common/io/velodyne_utility.cc +++ b/modules/localization/msf/common/io/velodyne_utility.cc @@ -19,7 +19,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/localization/msf/common/io/pcl_point_types.h" namespace apollo { diff --git a/modules/localization/msf/common/util/BUILD b/modules/localization/msf/common/util/BUILD index b3c005055b3..3bce0dc2da2 100644 --- a/modules/localization/msf/common/util/BUILD +++ b/modules/localization/msf/common/util/BUILD @@ -23,7 +23,7 @@ cc_library( "-lboost_system", ], deps = [ - "//cybertron", + "//cyber", "@eigen", ], ) diff --git a/modules/localization/msf/common/util/compression.cc b/modules/localization/msf/common/util/compression.cc index 09f1c7a907a..b38ff977670 100644 --- a/modules/localization/msf/common/util/compression.cc +++ b/modules/localization/msf/common/util/compression.cc @@ -19,7 +19,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace localization { diff --git a/modules/localization/msf/common/util/frame_transform.cc b/modules/localization/msf/common/util/frame_transform.cc index 9d9e9aabf80..802f9849f8a 100755 --- a/modules/localization/msf/common/util/frame_transform.cc +++ b/modules/localization/msf/common/util/frame_transform.cc @@ -15,7 +15,7 @@ *****************************************************************************/ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/localization/msf/common/util/frame_transform.h" namespace apollo { diff --git a/modules/localization/msf/common/util/threadpool.h b/modules/localization/msf/common/util/threadpool.h index b752f5e4300..8b589283f06 100755 --- a/modules/localization/msf/common/util/threadpool.h +++ b/modules/localization/msf/common/util/threadpool.h @@ -24,8 +24,8 @@ #include #include -#include "cybertron/common/log.h" -#include "cybertron/common/macros.h" +#include "cyber/common/log.h" +#include "cyber/common/macros.h" /// The namespace threadpool contains a thread pool and related utility classes. namespace apollo { diff --git a/modules/localization/msf/local_integ/gnss_msg_transfer.cc b/modules/localization/msf/local_integ/gnss_msg_transfer.cc index 3b564de552d..1a811ebf0fc 100644 --- a/modules/localization/msf/local_integ/gnss_msg_transfer.cc +++ b/modules/localization/msf/local_integ/gnss_msg_transfer.cc @@ -15,7 +15,7 @@ *****************************************************************************/ #include "modules/localization/msf/local_integ/gnss_msg_transfer.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace localization { diff --git a/modules/localization/msf/local_integ/lidar_msg_transfer.cc b/modules/localization/msf/local_integ/lidar_msg_transfer.cc index e07ba5f896d..7381b73e7d6 100644 --- a/modules/localization/msf/local_integ/lidar_msg_transfer.cc +++ b/modules/localization/msf/local_integ/lidar_msg_transfer.cc @@ -19,8 +19,8 @@ #include "Eigen/Core" #include "Eigen/Geometry" -#include "cybertron/common/log.h" -#include "cybertron/time/time.h" +#include "cyber/common/log.h" +#include "cyber/time/time.h" #include "modules/localization/common/localization_gflags.h" namespace apollo { @@ -78,7 +78,7 @@ void LidarMsgTransfer::Transfer(const drivers::PointCloud &msg, } lidar_frame->measurement_time = - cybertron::Time(msg.measurement_time()).ToSecond(); + cyber::Time(msg.measurement_time()).ToSecond(); if (FLAGS_lidar_debug_log_flag) { AINFO << std::setprecision(15) << "LocalLidar Debug Log: velodyne msg. " << "[time:" << lidar_frame->measurement_time diff --git a/modules/localization/msf/local_integ/localization_gnss_process.cc b/modules/localization/msf/local_integ/localization_gnss_process.cc index fe0784dcd68..9f3c032b9ab 100644 --- a/modules/localization/msf/local_integ/localization_gnss_process.cc +++ b/modules/localization/msf/local_integ/localization_gnss_process.cc @@ -20,7 +20,7 @@ #include "yaml-cpp/yaml.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/time/time.h" #include "modules/localization/msf/local_integ/gnss_msg_transfer.h" diff --git a/modules/localization/msf/local_integ/localization_integ_impl.cc b/modules/localization/msf/local_integ/localization_integ_impl.cc index cab79890922..8aaa37afac3 100644 --- a/modules/localization/msf/local_integ/localization_integ_impl.cc +++ b/modules/localization/msf/local_integ/localization_integ_impl.cc @@ -19,7 +19,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/time/timer.h" #include "modules/localization/msf/common/util/frame_transform.h" @@ -373,7 +373,7 @@ void LocalizationIntegImpl::RawObservationProcess( RawObservationProcessImpl(raw_obs_msg); - // TODO(zhouyao4321): Use cybertron::Task instead. + // TODO(zhouyao4321): Use cyber::Task instead. // // push process function to queue // gnss_function_queue_mutex_.lock(); // gnss_function_queue_.push(std::function(std::bind( @@ -393,7 +393,7 @@ void LocalizationIntegImpl::RawEphemerisProcess( RawEphemerisProcessImpl(gnss_orbit_msg); - // TODO(zhouyao4321): Use cybertron::Task instead. + // TODO(zhouyao4321): Use cyber::Task instead. // // push process function to queue // gnss_function_queue_mutex_.lock(); // gnss_function_queue_.push(std::function(std::bind( @@ -413,7 +413,7 @@ void LocalizationIntegImpl::GnssBestPoseProcess( GnssBestPoseProcessImpl(bestgnsspos_msg); - // TODO(zhouyao4321): Use cybertron::Task instead. + // TODO(zhouyao4321): Use cyber::Task instead. // // push process function to queue // gnss_function_queue_mutex_.lock(); // gnss_function_queue_.push(std::function(std::bind( diff --git a/modules/localization/msf/local_integ/localization_integ_process.cc b/modules/localization/msf/local_integ/localization_integ_process.cc index 5010b1e4ee4..bc1755bc770 100644 --- a/modules/localization/msf/local_integ/localization_integ_process.cc +++ b/modules/localization/msf/local_integ/localization_integ_process.cc @@ -19,7 +19,7 @@ #include #include "yaml-cpp/yaml.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/time/time.h" #include "modules/common/time/timer.h" #include "modules/localization/msf/common/util/frame_transform.h" @@ -251,7 +251,7 @@ void LocalizationIntegProcess::MeasureDataProcess( void LocalizationIntegProcess::StartThreadLoop() { keep_running_ = true; measure_data_queue_size_ = 150; - cybertron::Async(&LocalizationIntegProcess::MeasureDataThreadLoop, this); + cyber::Async(&LocalizationIntegProcess::MeasureDataThreadLoop, this); } void LocalizationIntegProcess::StopThreadLoop() { @@ -272,7 +272,7 @@ void LocalizationIntegProcess::MeasureDataThreadLoop() { } if (measure_data_queue_.size() == 0) { lock.unlock(); - cybertron::Yield(); + cyber::Yield(); continue; } } diff --git a/modules/localization/msf/local_integ/localization_integ_process.h b/modules/localization/msf/local_integ/localization_integ_process.h index 51bb95f3c0e..18695aecf3b 100644 --- a/modules/localization/msf/local_integ/localization_integ_process.h +++ b/modules/localization/msf/local_integ/localization_integ_process.h @@ -26,7 +26,7 @@ #include "Eigen/Core" #include "Eigen/Geometry" -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "include/sins.h" #include "modules/common/status/status.h" diff --git a/modules/localization/msf/local_integ/localization_lidar.h b/modules/localization/msf/local_integ/localization_lidar.h index efcb711eb82..2b8c2997419 100644 --- a/modules/localization/msf/local_integ/localization_lidar.h +++ b/modules/localization/msf/local_integ/localization_lidar.h @@ -19,7 +19,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/localization/msf/local_map/base_map/base_map_node_index.h" #include "modules/localization/msf/local_map/lossy_map/lossy_map_2d.h" #include "modules/localization/msf/local_map/lossy_map/lossy_map_config_2d.h" diff --git a/modules/localization/msf/local_integ/localization_lidar_process.cc b/modules/localization/msf/local_integ/localization_lidar_process.cc index c6c3b862ca6..603010ada70 100644 --- a/modules/localization/msf/local_integ/localization_lidar_process.cc +++ b/modules/localization/msf/local_integ/localization_lidar_process.cc @@ -18,7 +18,7 @@ #include "yaml-cpp/yaml.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/time/time.h" #include "modules/common/time/timer.h" #include "modules/common/util/file.h" diff --git a/modules/localization/msf/local_integ/measure_republish_process.cc b/modules/localization/msf/local_integ/measure_republish_process.cc index 21448c60d2b..b44e3f6e8c9 100644 --- a/modules/localization/msf/local_integ/measure_republish_process.cc +++ b/modules/localization/msf/local_integ/measure_republish_process.cc @@ -21,7 +21,7 @@ #include "yaml-cpp/yaml.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/math/euler_angles_zxy.h" #include "modules/common/time/time_util.h" diff --git a/modules/localization/msf/local_integ/online_localization_expert.cc b/modules/localization/msf/local_integ/online_localization_expert.cc index fe7947f1877..3606b71f2f5 100644 --- a/modules/localization/msf/local_integ/online_localization_expert.cc +++ b/modules/localization/msf/local_integ/online_localization_expert.cc @@ -16,7 +16,7 @@ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/time/time.h" #include "modules/localization/msf/local_integ/online_localization_expert.h" diff --git a/modules/localization/msf/local_map/base_map/base_map.cc b/modules/localization/msf/local_map/base_map/base_map.cc index cef567fd81b..e6337eb87ab 100644 --- a/modules/localization/msf/local_map/base_map/base_map.cc +++ b/modules/localization/msf/local_map/base_map/base_map.cc @@ -16,7 +16,7 @@ #include "modules/localization/msf/local_map/base_map/base_map.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/localization/msf/common/util/system_utility.h" namespace apollo { diff --git a/modules/localization/msf/local_map/base_map/base_map_node.cc b/modules/localization/msf/local_map/base_map/base_map_node.cc index 4f10ee41306..f86e43b665c 100644 --- a/modules/localization/msf/local_map/base_map/base_map_node.cc +++ b/modules/localization/msf/local_map/base_map/base_map_node.cc @@ -20,7 +20,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/file.h" #include "modules/localization/msf/local_map/base_map/base_map_matrix.h" diff --git a/modules/localization/msf/local_map/base_map/base_map_node_index.cc b/modules/localization/msf/local_map/base_map/base_map_node_index.cc index 88d17930d20..3190da2dc3e 100644 --- a/modules/localization/msf/local_map/base_map/base_map_node_index.cc +++ b/modules/localization/msf/local_map/base_map/base_map_node_index.cc @@ -19,7 +19,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace localization { diff --git a/modules/localization/msf/local_map/base_map/base_map_pool.cc b/modules/localization/msf/local_map/base_map/base_map_pool.cc index a899a64eab5..6d755b62b6c 100644 --- a/modules/localization/msf/local_map/base_map/base_map_pool.cc +++ b/modules/localization/msf/local_map/base_map/base_map_pool.cc @@ -16,7 +16,7 @@ #include "modules/localization/msf/local_map/base_map/base_map_pool.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/localization/msf/local_map/base_map/base_map_config.h" #include "modules/localization/msf/local_map/base_map/base_map_node.h" #include "modules/localization/msf/local_map/base_map/base_map_node_index.h" diff --git a/modules/localization/msf/local_map/lossless_map/lossless_map.cc b/modules/localization/msf/local_map/lossless_map/lossless_map.cc index 0db80f714cf..db86eeace82 100644 --- a/modules/localization/msf/local_map/lossless_map/lossless_map.cc +++ b/modules/localization/msf/local_map/lossless_map/lossless_map.cc @@ -18,7 +18,7 @@ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/localization/msf/local_map/lossless_map/lossless_map_node.h" namespace apollo { diff --git a/modules/localization/msf/local_map/lossless_map/lossless_map_matrix.h b/modules/localization/msf/local_map/lossless_map/lossless_map_matrix.h index d6a793e0161..b67bc9c71e1 100644 --- a/modules/localization/msf/local_map/lossless_map/lossless_map_matrix.h +++ b/modules/localization/msf/local_map/lossless_map/lossless_map_matrix.h @@ -18,7 +18,7 @@ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/localization/msf/local_map/base_map/base_map_matrix.h" #include "modules/localization/msf/local_map/base_map/base_map_node.h" diff --git a/modules/localization/msf/local_map/lossless_map/lossless_map_node.cc b/modules/localization/msf/local_map/lossless_map/lossless_map_node.cc index d56ca8c13f0..60bf0fdc866 100644 --- a/modules/localization/msf/local_map/lossless_map/lossless_map_node.cc +++ b/modules/localization/msf/local_map/lossless_map/lossless_map_node.cc @@ -18,7 +18,7 @@ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/localization/msf/local_map/lossless_map/lossless_map_config.h" namespace apollo { diff --git a/modules/localization/msf/local_map/test/BUILD b/modules/localization/msf/local_map/test/BUILD index bff4a89bd30..31cb348fdc8 100644 --- a/modules/localization/msf/local_map/test/BUILD +++ b/modules/localization/msf/local_map/test/BUILD @@ -27,7 +27,7 @@ cc_test( "-lboost_program_options", ], deps = [ - "//cybertron", + "//cyber", "//modules/localization/msf/common/util:localization_msf_common_util", "//modules/localization/msf/local_map/base_map:localization_msf_base_map", "//modules/localization/msf/local_map/lossless_map:localization_msf_lossless_map", diff --git a/modules/localization/msf/local_tool/data_extraction/BUILD b/modules/localization/msf/local_tool/data_extraction/BUILD index 57a92725c1c..400a6a0cb2c 100644 --- a/modules/localization/msf/local_tool/data_extraction/BUILD +++ b/modules/localization/msf/local_tool/data_extraction/BUILD @@ -20,7 +20,7 @@ cc_library( "-lboost_program_options", ], deps = [ - "//cybertron", + "//cyber", "//modules/common/math", "//modules/localization/proto:gps_proto", "//modules/localization/proto:localization_proto", @@ -45,7 +45,7 @@ cc_binary( linkstatic = 0, deps = [ ":data_extraction", - "//cybertron", + "//cyber", "@eigen//:eigen", "@pcl//:pcl", ], @@ -64,7 +64,7 @@ cc_binary( linkstatic = 0, deps = [ ":data_extraction", - "//cybertron", + "//cyber", "@eigen//:eigen", ], ) diff --git a/modules/localization/msf/local_tool/data_extraction/compare_poses.cc b/modules/localization/msf/local_tool/data_extraction/compare_poses.cc index 1a5f4034c5b..85ba1cb67d1 100644 --- a/modules/localization/msf/local_tool/data_extraction/compare_poses.cc +++ b/modules/localization/msf/local_tool/data_extraction/compare_poses.cc @@ -26,7 +26,7 @@ #include "boost/program_options.hpp" #include "yaml-cpp/yaml.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/math/quaternion.h" #include "modules/localization/msf/common/io/velodyne_utility.h" diff --git a/modules/localization/msf/local_tool/data_extraction/cyber_record_parser.cc b/modules/localization/msf/local_tool/data_extraction/cyber_record_parser.cc index 9322b9b7f24..875bffaf831 100644 --- a/modules/localization/msf/local_tool/data_extraction/cyber_record_parser.cc +++ b/modules/localization/msf/local_tool/data_extraction/cyber_record_parser.cc @@ -16,7 +16,7 @@ #include #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/localization/msf/local_tool/data_extraction/cyber_record_reader.h" #include "modules/localization/msf/local_tool/data_extraction/location_exporter.h" #include "modules/localization/msf/local_tool/data_extraction/pcd_exporter.h" diff --git a/modules/localization/msf/local_tool/data_extraction/cyber_record_reader.cc b/modules/localization/msf/local_tool/data_extraction/cyber_record_reader.cc index 32a1c10a010..94dc770e268 100644 --- a/modules/localization/msf/local_tool/data_extraction/cyber_record_reader.cc +++ b/modules/localization/msf/local_tool/data_extraction/cyber_record_reader.cc @@ -19,14 +19,14 @@ #include #include -#include "cybertron/cybertron.h" -#include "cybertron/record/record_reader.h" +#include "cyber/cyber.h" +#include "cyber/record/record_reader.h" namespace apollo { namespace localization { namespace msf { -using cybertron::record::RecordReader; +using cyber::record::RecordReader; CyberRecordReader::CyberRecordReader() {} @@ -41,7 +41,7 @@ void CyberRecordReader::Subscribe( void CyberRecordReader::Read(const std::string &file_name) { RecordReader reader(file_name); - cybertron::record::RecordMessage message; + cyber::record::RecordMessage message; while (reader.ReadMessage(&message)) { auto itr = call_back_map_.find(message.channel_name); if (itr != call_back_map_.end()) { diff --git a/modules/localization/msf/local_tool/data_extraction/location_exporter.cc b/modules/localization/msf/local_tool/data_extraction/location_exporter.cc index 7242e4dd084..8733c9d70a7 100644 --- a/modules/localization/msf/local_tool/data_extraction/location_exporter.cc +++ b/modules/localization/msf/local_tool/data_extraction/location_exporter.cc @@ -22,7 +22,7 @@ #include "modules/localization/proto/measure.pb.h" #include "modules/localization/proto/gps.pb.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace localization { diff --git a/modules/localization/msf/local_tool/data_extraction/pcd_exporter.cc b/modules/localization/msf/local_tool/data_extraction/pcd_exporter.cc index 9a45d01f1e9..40b3574b86c 100644 --- a/modules/localization/msf/local_tool/data_extraction/pcd_exporter.cc +++ b/modules/localization/msf/local_tool/data_extraction/pcd_exporter.cc @@ -18,7 +18,7 @@ #include #include "pcl/io/pcd_io.h" #include "pcl/point_types.h" -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/localization/msf/common/io/pcl_point_types.h" namespace apollo { @@ -52,7 +52,7 @@ void PCDExporter::CompensatedPcdCallback(const std::string &msg_string) { std::string pcd_filename = ss_pcd.str(); WritePcdFile(pcd_filename, msg); - double timestamp = cybertron::Time(msg.measurement_time()).ToSecond(); + double timestamp = cyber::Time(msg.measurement_time()).ToSecond(); fprintf(stamp_file_handle_, "%u %lf\n", index, timestamp); ++index; diff --git a/modules/localization/msf/local_tool/local_visualization/engine/BUILD b/modules/localization/msf/local_tool/local_visualization/engine/BUILD index 113f11a7d65..31314cd9c7e 100644 --- a/modules/localization/msf/local_tool/local_visualization/engine/BUILD +++ b/modules/localization/msf/local_tool/local_visualization/engine/BUILD @@ -22,7 +22,7 @@ cc_library( "-lboost_program_options", ], deps = [ - "//cybertron", + "//cyber", "//modules/common/util", "//modules/localization/msf/common/io:localization_msf_common_io", "//modules/localization/msf/local_map/base_map:localization_msf_base_map", diff --git a/modules/localization/msf/local_tool/local_visualization/engine/visualization_engine.cc b/modules/localization/msf/local_tool/local_visualization/engine/visualization_engine.cc index 67b42b7be66..185421dba25 100644 --- a/modules/localization/msf/local_tool/local_visualization/engine/visualization_engine.cc +++ b/modules/localization/msf/local_tool/local_visualization/engine/visualization_engine.cc @@ -21,7 +21,7 @@ #include "boost/filesystem.hpp" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/file.h" namespace apollo { diff --git a/modules/localization/msf/local_tool/local_visualization/engine/visualization_manager.cc b/modules/localization/msf/local_tool/local_visualization/engine/visualization_manager.cc index ba54a0f94ca..6379e5d5d30 100644 --- a/modules/localization/msf/local_tool/local_visualization/engine/visualization_manager.cc +++ b/modules/localization/msf/local_tool/local_visualization/engine/visualization_manager.cc @@ -23,7 +23,7 @@ #include "boost/date_time/posix_time/posix_time.hpp" #include "boost/filesystem.hpp" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace localization { diff --git a/modules/localization/msf/local_tool/local_visualization/offline_visual/BUILD b/modules/localization/msf/local_tool/local_visualization/offline_visual/BUILD index dc05d0a8180..90046ecf1f4 100644 --- a/modules/localization/msf/local_tool/local_visualization/offline_visual/BUILD +++ b/modules/localization/msf/local_tool/local_visualization/offline_visual/BUILD @@ -16,7 +16,7 @@ cc_library( "-lboost_program_options", ], deps = [ - "//cybertron", + "//cyber", "//modules/common/util", "//modules/localization/msf/common/io:localization_msf_common_io", "//modules/localization/msf/local_map/base_map:localization_msf_base_map", @@ -38,7 +38,7 @@ cc_binary( linkstatic = 0, deps = [ ":offline_local_visualizer_lib", - "//cybertron", + "//cyber", "//modules/localization/msf/common/io:localization_msf_common_io", "//modules/localization/msf/local_map/base_map:localization_msf_base_map", "@eigen//:eigen", diff --git a/modules/localization/msf/local_tool/local_visualization/offline_visual/offline_local_visualizer.cc b/modules/localization/msf/local_tool/local_visualization/offline_visual/offline_local_visualizer.cc index 41cfbf0c7e4..8bdd2140cc2 100644 --- a/modules/localization/msf/local_tool/local_visualization/offline_visual/offline_local_visualizer.cc +++ b/modules/localization/msf/local_tool/local_visualization/offline_visual/offline_local_visualizer.cc @@ -21,7 +21,7 @@ #include "boost/filesystem.hpp" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/localization/msf/common/io/velodyne_utility.h" namespace apollo { diff --git a/modules/localization/msf/local_tool/local_visualization/online_visual/BUILD b/modules/localization/msf/local_tool/local_visualization/online_visual/BUILD index 38625fd4c70..1c35c26083e 100644 --- a/modules/localization/msf/local_tool/local_visualization/online_visual/BUILD +++ b/modules/localization/msf/local_tool/local_visualization/online_visual/BUILD @@ -20,7 +20,7 @@ cc_library( "-lboost_program_options", ], deps = [ - "//cybertron", + "//cyber", "//modules/common/proto:geometry_proto", "//modules/common/status", "//modules/common/time", diff --git a/modules/localization/msf/local_tool/local_visualization/online_visual/online_visualizer_component.cc b/modules/localization/msf/local_tool/local_visualization/online_visual/online_visualizer_component.cc index 7d87e134c16..69459d60773 100644 --- a/modules/localization/msf/local_tool/local_visualization/online_visual/online_visualizer_component.cc +++ b/modules/localization/msf/local_tool/local_visualization/online_visual/online_visualizer_component.cc @@ -61,7 +61,7 @@ bool OnlineVisualizerComponent::Init() { bool OnlineVisualizerComponent::InitConfig() { msf_config::Config msf_config; - if (!apollo::cybertron::common::GetProtoFromFile(config_file_path_, + if (!apollo::cyber::common::GetProtoFromFile(config_file_path_, &msf_config)) { return false; } @@ -140,7 +140,7 @@ bool OnlineVisualizerComponent::Proc( const std::shared_ptr &msg) { LidarVisFrame lidar_vis_frame; lidar_vis_frame.timestamp = - cybertron::Time(msg->measurement_time()).ToSecond(); + cyber::Time(msg->measurement_time()).ToSecond(); std::vector intensities; ParsePointCloudMessage(msg, &lidar_vis_frame.pt3ds, &intensities); diff --git a/modules/localization/msf/local_tool/local_visualization/online_visual/online_visualizer_component.h b/modules/localization/msf/local_tool/local_visualization/online_visual/online_visualizer_component.h index 8797189dc64..0a42667497f 100644 --- a/modules/localization/msf/local_tool/local_visualization/online_visual/online_visualizer_component.h +++ b/modules/localization/msf/local_tool/local_visualization/online_visual/online_visualizer_component.h @@ -31,7 +31,7 @@ #include "glog/logging.h" #include "gtest/gtest_prod.h" -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/drivers/proto/pointcloud.pb.h" #include "modules/localization/proto/localization.pb.h" @@ -48,7 +48,7 @@ namespace localization { namespace msf { class OnlineVisualizerComponent final - : public cybertron::Component { + : public cyber::Component { public: OnlineVisualizerComponent(); ~OnlineVisualizerComponent(); @@ -80,20 +80,20 @@ class OnlineVisualizerComponent final std::string map_folder_; std::string map_visual_folder_; - std::shared_ptr> + std::shared_ptr> lidar_local_listener_ = nullptr; std::string lidar_local_topic_ = ""; - std::shared_ptr> + std::shared_ptr> gnss_local_listener_ = nullptr; std::string gnss_local_topic_ = ""; - std::shared_ptr> + std::shared_ptr> fusion_local_listener_ = nullptr; std::string fusion_local_topic_ = ""; }; -CYBERTRON_REGISTER_COMPONENT(OnlineVisualizerComponent); +CYBER_REGISTER_COMPONENT(OnlineVisualizerComponent); } // namespace msf } // namespace localization diff --git a/modules/localization/msf/local_tool/map_creation/BUILD b/modules/localization/msf/local_tool/map_creation/BUILD index 5fa63c76ebc..83ceac51bf0 100644 --- a/modules/localization/msf/local_tool/map_creation/BUILD +++ b/modules/localization/msf/local_tool/map_creation/BUILD @@ -14,7 +14,7 @@ cc_binary( ], linkstatic = 0, deps = [ - "//cybertron", + "//cyber", "//modules/localization/msf/common/io:localization_msf_common_io", "//modules/localization/msf/common/util:localization_msf_common_util", "//modules/localization/msf/local_map/base_map:localization_msf_base_map", @@ -35,7 +35,7 @@ cc_binary( ], linkstatic = 0, deps = [ - "//cybertron", + "//cyber", "//modules/localization/msf/common/io:localization_msf_common_io", "//modules/localization/msf/common/util:localization_msf_common_util", "//modules/localization/msf/local_map/base_map:localization_msf_base_map", diff --git a/modules/localization/msf/msf_localization.h b/modules/localization/msf/msf_localization.h index d27b981b1ab..f9602529e0e 100644 --- a/modules/localization/msf/msf_localization.h +++ b/modules/localization/msf/msf_localization.h @@ -38,7 +38,7 @@ #include "modules/localization/proto/localization.pb.h" #include "modules/localization/proto/msf_config.pb.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/monitor_log/monitor_log_buffer.h" #include "modules/common/status/status.h" #include "modules/localization/msf/local_integ/localization_integ.h" diff --git a/modules/localization/msf/msf_localization_component.cc b/modules/localization/msf/msf_localization_component.cc index a1b4f8c8c6f..ea6c174209e 100644 --- a/modules/localization/msf/msf_localization_component.cc +++ b/modules/localization/msf/msf_localization_component.cc @@ -27,12 +27,12 @@ namespace apollo { namespace localization { using apollo::common::time::Clock; -using apollo::cybertron::proto::RoleAttributes; +using apollo::cyber::proto::RoleAttributes; MSFLocalizationComponent::MSFLocalizationComponent() {} bool MSFLocalizationComponent::Init() { - Clock::SetMode(Clock::CYBERTRON); + Clock::SetMode(Clock::CYBER); publisher_.reset(new LocalizationMsgPublisher(this->node_)); if (InitConfig() != true) { @@ -50,7 +50,7 @@ bool MSFLocalizationComponent::Init() { bool MSFLocalizationComponent::InitConfig() { msf_config::Config msf_config; - if (!apollo::cybertron::common::GetProtoFromFile(config_file_path_, + if (!apollo::cyber::common::GetProtoFromFile(config_file_path_, &msf_config)) { return false; } @@ -73,7 +73,7 @@ bool MSFLocalizationComponent::InitConfig() { } bool MSFLocalizationComponent::InitIO() { - cybertron::ReaderConfig reader_config; + cyber::ReaderConfig reader_config; reader_config.channel_name = lidar_topic_; reader_config.pending_queue_size = 1; @@ -110,7 +110,7 @@ bool MSFLocalizationComponent::Proc( } LocalizationMsgPublisher::LocalizationMsgPublisher( - const std::shared_ptr& node) + const std::shared_ptr& node) : node_(node), tf2_broadcaster_(node) {} bool LocalizationMsgPublisher::InitConfig(const msf_config::Config& config) { diff --git a/modules/localization/msf/msf_localization_component.h b/modules/localization/msf/msf_localization_component.h index 568790ddfc8..40085250f6c 100644 --- a/modules/localization/msf/msf_localization_component.h +++ b/modules/localization/msf/msf_localization_component.h @@ -22,10 +22,10 @@ #include #include -#include "cybertron/class_loader/class_loader.h" -#include "cybertron/component/component.h" -#include "cybertron/cybertron.h" -#include "cybertron/message/raw_message.h" +#include "cyber/class_loader/class_loader.h" +#include "cyber/component/component.h" +#include "cyber/cyber.h" +#include "cyber/message/raw_message.h" #include "modules/localization/msf/msf_localization.h" @@ -41,7 +41,7 @@ namespace apollo { namespace localization { class MSFLocalizationComponent final - : public cybertron::Component { + : public cyber::Component { public: MSFLocalizationComponent(); ~MSFLocalizationComponent() = default; @@ -55,11 +55,11 @@ class MSFLocalizationComponent final bool InitIO(); private: - std::shared_ptr> lidar_listener_ = + std::shared_ptr> lidar_listener_ = nullptr; std::string lidar_topic_ = ""; - std::shared_ptr> + std::shared_ptr> bestgnsspos_listener_ = nullptr; std::string bestgnsspos_topic_ = ""; @@ -68,12 +68,12 @@ class MSFLocalizationComponent final MSFLocalization localization_; }; -CYBERTRON_REGISTER_COMPONENT(MSFLocalizationComponent); +CYBER_REGISTER_COMPONENT(MSFLocalizationComponent); class LocalizationMsgPublisher { public: explicit LocalizationMsgPublisher( - const std::shared_ptr& node); + const std::shared_ptr& node); ~LocalizationMsgPublisher() = default; bool InitConfig(const msf_config::Config& config); @@ -87,10 +87,10 @@ class LocalizationMsgPublisher { void PublishLocalizationStatus(const LocalizationStatus& localization_status); private: - std::shared_ptr node_; + std::shared_ptr node_; std::string localization_topic_ = ""; - std::shared_ptr> + std::shared_ptr> localization_talker_ = nullptr; std::string broadcast_tf_frame_id_ = ""; @@ -98,15 +98,15 @@ class LocalizationMsgPublisher { apollo::transform::TransformBroadcaster tf2_broadcaster_; std::string lidar_local_topic_ = ""; - std::shared_ptr> lidar_local_talker_ = + std::shared_ptr> lidar_local_talker_ = nullptr; std::string gnss_local_topic_ = ""; - std::shared_ptr> gnss_local_talker_ = + std::shared_ptr> gnss_local_talker_ = nullptr; std::string localization_status_topic_ = ""; - std::shared_ptr> + std::shared_ptr> localization_status_talker_ = nullptr; }; diff --git a/modules/localization/rtk/BUILD b/modules/localization/rtk/BUILD index b57f275aa36..526fd80e64b 100644 --- a/modules/localization/rtk/BUILD +++ b/modules/localization/rtk/BUILD @@ -24,7 +24,7 @@ cc_library( "//modules/localization/proto:gps_proto", "//modules/localization/proto:imu_proto", "//modules/transform:transform_broadcaster_lib", - "//cybertron", + "//cyber", "@eigen", "@gtest", ], @@ -45,7 +45,7 @@ cc_test( ], data = ["//modules/localization:localization_testdata"], deps = [ - "//cybertron", + "//cyber", "//modules/common/time", "//modules/common/util", "//modules/localization/rtk:rtk_localization_component_lib", diff --git a/modules/localization/rtk/rtk_localization_component.cc b/modules/localization/rtk/rtk_localization_component.cc index f22f535d9f7..d9f77c69837 100644 --- a/modules/localization/rtk/rtk_localization_component.cc +++ b/modules/localization/rtk/rtk_localization_component.cc @@ -26,7 +26,7 @@ RTKLocalizationComponent::RTKLocalizationComponent() : localization_(new RTKLocalization()) {} bool RTKLocalizationComponent::Init() { - Clock::SetMode(Clock::CYBERTRON); + Clock::SetMode(Clock::CYBER); tf2_broadcaster_.reset(new apollo::transform::TransformBroadcaster(node_)); if (InitConfig() != true) { AERROR << "Init Config falseed."; @@ -43,7 +43,7 @@ bool RTKLocalizationComponent::Init() { bool RTKLocalizationComponent::InitConfig() { rtk_config::Config rtk_config; - if (!apollo::cybertron::common::GetProtoFromFile(config_file_path_, + if (!apollo::cyber::common::GetProtoFromFile(config_file_path_, &rtk_config)) { return false; } diff --git a/modules/localization/rtk/rtk_localization_component.h b/modules/localization/rtk/rtk_localization_component.h index fe822ae4dcd..8d7f8e01929 100644 --- a/modules/localization/rtk/rtk_localization_component.h +++ b/modules/localization/rtk/rtk_localization_component.h @@ -20,10 +20,10 @@ #include #include -#include "cybertron/class_loader/class_loader.h" -#include "cybertron/component/component.h" -#include "cybertron/cybertron.h" -#include "cybertron/message/raw_message.h" +#include "cyber/class_loader/class_loader.h" +#include "cyber/component/component.h" +#include "cyber/cyber.h" +#include "cyber/message/raw_message.h" #include "modules/localization/proto/gps.pb.h" #include "modules/localization/proto/imu.pb.h" @@ -36,7 +36,7 @@ namespace apollo { namespace localization { class RTKLocalizationComponent final - : public cybertron::Component { + : public cyber::Component { public: RTKLocalizationComponent(); ~RTKLocalizationComponent() = default; @@ -55,10 +55,10 @@ class RTKLocalizationComponent final void PublishPoseBroadcastTopic(const LocalizationEstimate &localization); private: - std::shared_ptr> + std::shared_ptr> corrected_imu_listener_ = nullptr; - std::shared_ptr> + std::shared_ptr> localization_talker_ = nullptr; std::string localization_topic_ = ""; @@ -72,7 +72,7 @@ class RTKLocalizationComponent final std::unique_ptr localization_; }; -CYBERTRON_REGISTER_COMPONENT(RTKLocalizationComponent); +CYBER_REGISTER_COMPONENT(RTKLocalizationComponent); } // namespace localization } // namespace apollo diff --git a/modules/localization/rtk/rtk_localization_test.cc b/modules/localization/rtk/rtk_localization_test.cc index b1c3c0aab8f..8c4f97da89c 100644 --- a/modules/localization/rtk/rtk_localization_test.cc +++ b/modules/localization/rtk/rtk_localization_test.cc @@ -19,7 +19,7 @@ #include "google/protobuf/text_format.h" #include "gtest/gtest.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/util.h" namespace apollo { diff --git a/modules/map/hdmap/BUILD b/modules/map/hdmap/BUILD index f15f268884d..e68980d40c2 100644 --- a/modules/map/hdmap/BUILD +++ b/modules/map/hdmap/BUILD @@ -33,7 +33,7 @@ cc_library( hdrs = ["hdmap_util.h"], deps = [ ":hdmap", - "//cybertron", + "//cyber", "//modules/common/configs:config_gflags", "//modules/common/util", "//modules/common/util:string_util", diff --git a/modules/map/hdmap/adapter/BUILD b/modules/map/hdmap/adapter/BUILD index 0ce8206c519..de0d578658e 100644 --- a/modules/map/hdmap/adapter/BUILD +++ b/modules/map/hdmap/adapter/BUILD @@ -31,7 +31,7 @@ cc_library( "xml_parser/util_xml_parser.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/common/math", "//modules/common/status", "//modules/common/util", diff --git a/modules/map/hdmap/adapter/opendrive_adapter.cc b/modules/map/hdmap/adapter/opendrive_adapter.cc index 889bb04105f..06eee841537 100644 --- a/modules/map/hdmap/adapter/opendrive_adapter.cc +++ b/modules/map/hdmap/adapter/opendrive_adapter.cc @@ -16,7 +16,7 @@ limitations under the License. #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/map/hdmap/adapter/proto_organizer.h" #include "modules/map/hdmap/adapter/xml_parser/status.h" diff --git a/modules/map/hdmap/adapter/proto_organizer.cc b/modules/map/hdmap/adapter/proto_organizer.cc index d8b5e60e52f..f1245f7037b 100644 --- a/modules/map/hdmap/adapter/proto_organizer.cc +++ b/modules/map/hdmap/adapter/proto_organizer.cc @@ -22,7 +22,7 @@ limitations under the License. #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/math/polygon2d.h" #include "modules/common/math/vec2d.h" diff --git a/modules/map/hdmap/adapter/xml_parser/common_define.h b/modules/map/hdmap/adapter/xml_parser/common_define.h index 6ff2927af86..016a844a99b 100644 --- a/modules/map/hdmap/adapter/xml_parser/common_define.h +++ b/modules/map/hdmap/adapter/xml_parser/common_define.h @@ -17,7 +17,7 @@ limitations under the License. #include #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/map/proto/map.pb.h" namespace apollo { diff --git a/modules/map/hdmap/adapter/xml_parser/util_xml_parser.cc b/modules/map/hdmap/adapter/xml_parser/util_xml_parser.cc index e496a92726a..dc81fbaea2a 100644 --- a/modules/map/hdmap/adapter/xml_parser/util_xml_parser.cc +++ b/modules/map/hdmap/adapter/xml_parser/util_xml_parser.cc @@ -21,7 +21,7 @@ limitations under the License. #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/map/hdmap/adapter/coordinate_convert_tool.h" namespace apollo { diff --git a/modules/map/hdmap/hdmap.h b/modules/map/hdmap/hdmap.h index f2e6c83d9e6..692a7259377 100644 --- a/modules/map/hdmap/hdmap.h +++ b/modules/map/hdmap/hdmap.h @@ -20,7 +20,7 @@ #include #include -#include "cybertron/common/macros.h" +#include "cyber/common/macros.h" #include "modules/common/proto/geometry.pb.h" #include "modules/map/proto/map_clear_area.pb.h" diff --git a/modules/map/hdmap/hdmap_common.cc b/modules/map/hdmap/hdmap_common.cc index 022f15ae194..cfe38667e88 100644 --- a/modules/map/hdmap/hdmap_common.cc +++ b/modules/map/hdmap/hdmap_common.cc @@ -19,7 +19,7 @@ limitations under the License. #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/math/linear_interpolation.h" #include "modules/common/math/math_utils.h" #include "modules/map/hdmap/hdmap_impl.h" diff --git a/modules/map/pnc_map/BUILD b/modules/map/pnc_map/BUILD index 230d4907c04..6f20291615b 100644 --- a/modules/map/pnc_map/BUILD +++ b/modules/map/pnc_map/BUILD @@ -12,7 +12,7 @@ cuda_library( "cuda_util.h", ], deps = [ - "//cybertron", + "//cyber", "@cuda", ], ) @@ -98,7 +98,7 @@ cc_test( ], deps = [ ":path", - "//cybertron", + "//cyber", "//modules/common/util", "@gtest//:main", ], @@ -116,7 +116,7 @@ cc_test( ], deps = [ ":pnc_map", - "//cybertron", + "//cyber", "//modules/common/util", "@gtest//:main", ], @@ -134,7 +134,7 @@ cc_test( ], deps = [ ":route_segments", - "//cybertron", + "//cyber", "//modules/common/util", "@gtest//:main", ], diff --git a/modules/map/pnc_map/cuda_util.cu b/modules/map/pnc_map/cuda_util.cu index 64c94f4ceb4..6ce4a75746a 100644 --- a/modules/map/pnc_map/cuda_util.cu +++ b/modules/map/pnc_map/cuda_util.cu @@ -16,7 +16,7 @@ #include "modules/map/pnc_map/cuda_util.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include #include diff --git a/modules/map/pnc_map/path.h b/modules/map/pnc_map/path.h index f65d24272e3..4e6e13537a8 100644 --- a/modules/map/pnc_map/path.h +++ b/modules/map/pnc_map/path.h @@ -26,7 +26,7 @@ #include "modules/map/proto/map_lane.pb.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/math/box2d.h" #include "modules/common/math/line_segment2d.h" #include "modules/common/math/vec2d.h" diff --git a/modules/map/pnc_map/pnc_map.cc b/modules/map/pnc_map/pnc_map.cc index 8d60b55d689..3831250fde4 100644 --- a/modules/map/pnc_map/pnc_map.cc +++ b/modules/map/pnc_map/pnc_map.cc @@ -31,7 +31,7 @@ #include "modules/map/proto/map_id.pb.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/string_util.h" #include "modules/common/util/util.h" #include "modules/map/hdmap/hdmap_util.h" diff --git a/modules/map/relative_map/BUILD b/modules/map/relative_map/BUILD index 07f29c0756d..bc4b2968aca 100644 --- a/modules/map/relative_map/BUILD +++ b/modules/map/relative_map/BUILD @@ -41,7 +41,7 @@ cc_library( "navigation_lane.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/common/proto:pnc_point_proto", "//modules/common/vehicle_state:vehicle_state_provider", "//modules/localization/proto:localization_proto", @@ -63,7 +63,7 @@ cc_library( deps = [ ":relative_map_lib", "//external:gflags", - "//cybertron", + "//cyber", "//modules/common/adapters:adapter_gflags", ], ) diff --git a/modules/map/relative_map/launch/relative_map.launch b/modules/map/relative_map/launch/relative_map.launch index f8343864676..118917f2af8 100644 --- a/modules/map/relative_map/launch/relative_map.launch +++ b/modules/map/relative_map/launch/relative_map.launch @@ -1,7 +1,7 @@ - + relative_map /apollo/modules/map/relative_map/dag/relative_map.dag relative_map - + diff --git a/modules/map/relative_map/navigation_lane.cc b/modules/map/relative_map/navigation_lane.cc index 740ac3a766f..d6d481fcd67 100644 --- a/modules/map/relative_map/navigation_lane.cc +++ b/modules/map/relative_map/navigation_lane.cc @@ -22,7 +22,7 @@ #include "modules/map/proto/map_lane.pb.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/math/math_utils.h" #include "modules/common/math/vec2d.h" #include "modules/common/util/util.h" diff --git a/modules/map/relative_map/relative_map_component.h b/modules/map/relative_map/relative_map_component.h index b3e216e0412..e3b2a40f8e5 100644 --- a/modules/map/relative_map/relative_map_component.h +++ b/modules/map/relative_map/relative_map_component.h @@ -18,8 +18,8 @@ #include -#include "cybertron/component/timer_component.h" -#include "cybertron/cybertron.h" +#include "cyber/component/timer_component.h" +#include "cyber/cyber.h" #include "modules/map/relative_map/relative_map.h" @@ -27,7 +27,7 @@ namespace apollo { namespace relative_map { class RelativeMapComponent final - : public ::apollo::cybertron::TimerComponent { + : public ::apollo::cyber::TimerComponent { public: bool Init() override; @@ -36,20 +36,20 @@ class RelativeMapComponent final private: bool InitReaders(); - std::shared_ptr<::apollo::cybertron::Writer> + std::shared_ptr<::apollo::cyber::Writer> relative_map_writer_ = nullptr; - std::shared_ptr> + std::shared_ptr> perception_reader_ = nullptr; - std::shared_ptr> + std::shared_ptr> chassis_reader_ = nullptr; - std::shared_ptr> + std::shared_ptr> localization_reader_ = nullptr; - std::shared_ptr> + std::shared_ptr> navigation_reader_ = nullptr; RelativeMap relative_map_; }; -CYBERTRON_REGISTER_COMPONENT(RelativeMapComponent) +CYBER_REGISTER_COMPONENT(RelativeMapComponent) } // namespace relative_map } // namespace apollo diff --git a/modules/map/relative_map/tools/navigation_dummy.cc b/modules/map/relative_map/tools/navigation_dummy.cc index 6649393d92a..19190ec0418 100644 --- a/modules/map/relative_map/tools/navigation_dummy.cc +++ b/modules/map/relative_map/tools/navigation_dummy.cc @@ -22,7 +22,7 @@ #include "modules/common/adapters/adapter_manager.h" #include "modules/common/adapters/proto/adapter_config.pb.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/map/relative_map/proto/navigation.pb.h" DEFINE_string(navigation_dummy_file, diff --git a/modules/map/relative_map/tools/navigator.cc b/modules/map/relative_map/tools/navigator.cc index 08e88c0c96b..9b1d3dde45b 100644 --- a/modules/map/relative_map/tools/navigator.cc +++ b/modules/map/relative_map/tools/navigator.cc @@ -24,7 +24,7 @@ #include "modules/common/adapters/adapter_manager.h" #include "modules/common/adapters/proto/adapter_config.pb.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/map/relative_map/common/relative_map_gflags.h" #include "modules/map/relative_map/proto/navigation.pb.h" diff --git a/modules/map/tools/map_tool.cc b/modules/map/tools/map_tool.cc index a206185da28..1f41b6c3756 100644 --- a/modules/map/tools/map_tool.cc +++ b/modules/map/tools/map_tool.cc @@ -19,7 +19,7 @@ #include "gflags/gflags.h" #include "modules/common/configs/config_gflags.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/file.h" #include "modules/map/hdmap/hdmap_util.h" #include "modules/map/proto/map.pb.h" diff --git a/modules/map/tools/map_xysl.cc b/modules/map/tools/map_xysl.cc index 3ba9db0fde0..5175b16a5e4 100644 --- a/modules/map/tools/map_xysl.cc +++ b/modules/map/tools/map_xysl.cc @@ -20,7 +20,7 @@ #include "gflags/gflags.h" #include "modules/common/configs/config_gflags.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/file.h" #include "modules/common/util/string_util.h" #include "modules/map/hdmap/hdmap_common.h" diff --git a/modules/map/tools/proto_map_generator.cc b/modules/map/tools/proto_map_generator.cc index 84e21d29a48..25b29de249a 100644 --- a/modules/map/tools/proto_map_generator.cc +++ b/modules/map/tools/proto_map_generator.cc @@ -17,7 +17,7 @@ limitations under the License. #include "gflags/gflags.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/file.h" #include "modules/map/hdmap/adapter/opendrive_adapter.h" #include "modules/map/hdmap/hdmap_util.h" diff --git a/modules/map/tools/quaternion_euler.cc b/modules/map/tools/quaternion_euler.cc index 1b13a7442f1..ea325beaff0 100644 --- a/modules/map/tools/quaternion_euler.cc +++ b/modules/map/tools/quaternion_euler.cc @@ -18,7 +18,7 @@ #include "gflags/gflags.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/math/euler_angles_zxy.h" #include "modules/common/math/quaternion.h" diff --git a/modules/map/tools/refresh_default_end_way_point.cc b/modules/map/tools/refresh_default_end_way_point.cc index 578df0cba91..8ad501a84e4 100644 --- a/modules/map/tools/refresh_default_end_way_point.cc +++ b/modules/map/tools/refresh_default_end_way_point.cc @@ -26,7 +26,7 @@ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/file.h" #include "modules/map/hdmap/hdmap_util.h" #include "modules/routing/proto/poi.pb.h" diff --git a/modules/map/tools/sim_map_generator.cc b/modules/map/tools/sim_map_generator.cc index ad05acca0fb..26a6a2b4af1 100644 --- a/modules/map/tools/sim_map_generator.cc +++ b/modules/map/tools/sim_map_generator.cc @@ -20,7 +20,7 @@ #include "gflags/gflags.h" #include "modules/common/configs/config_gflags.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/file.h" #include "modules/common/util/points_downsampler.h" #include "modules/map/hdmap/adapter/opendrive_adapter.h" diff --git a/modules/monitor/BUILD b/modules/monitor/BUILD index be5997f2e8f..660a78d6ad2 100644 --- a/modules/monitor/BUILD +++ b/modules/monitor/BUILD @@ -9,7 +9,7 @@ cc_binary( "monitor.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/common/util:message_util", "//modules/monitor/common:recurrent_runner", "//modules/monitor/hardware/gps:gps_monitor", diff --git a/modules/monitor/common/BUILD b/modules/monitor/common/BUILD index e97a98baca5..20b6488d982 100644 --- a/modules/monitor/common/BUILD +++ b/modules/monitor/common/BUILD @@ -8,7 +8,7 @@ cc_library( hdrs = ["recurrent_runner.h"], deps = [ ":monitor_manager", - "//cybertron", + "//cyber", "//modules/common/time", ], ) diff --git a/modules/monitor/common/monitor_manager.cc b/modules/monitor/common/monitor_manager.cc index 68f8202e3ef..e88807b6631 100644 --- a/modules/monitor/common/monitor_manager.cc +++ b/modules/monitor/common/monitor_manager.cc @@ -40,7 +40,7 @@ MonitorManager::MonitorManager() : } void MonitorManager::Init( - const std::shared_ptr& node) { + const std::shared_ptr& node) { Instance()->node_ = node; } diff --git a/modules/monitor/common/monitor_manager.h b/modules/monitor/common/monitor_manager.h index 997a39508e6..52732c47ce7 100644 --- a/modules/monitor/common/monitor_manager.h +++ b/modules/monitor/common/monitor_manager.h @@ -20,7 +20,7 @@ #include #include -#include "cybertron/common/macros.h" +#include "cyber/common/macros.h" #include "modules/common/monitor_log/monitor_log_buffer.h" #include "modules/monitor/proto/monitor_conf.pb.h" #include "modules/monitor/proto/system_status.pb.h" @@ -34,25 +34,25 @@ namespace monitor { class MonitorManager { public: - static void Init(const std::shared_ptr& node); + static void Init(const std::shared_ptr& node); - static inline std::shared_ptr CurrentNode() { + static inline std::shared_ptr CurrentNode() { return Instance()->node_; } template - static inline std::shared_ptr> CreateReader( + static inline std::shared_ptr> CreateReader( const std::string& channel) { auto* readers = &(Instance()->readers_); if (readers->find(channel) == readers->end()) { readers->emplace(channel, CHECK_NOTNULL(CurrentNode())->CreateReader(channel)); } - return std::dynamic_pointer_cast>((*readers)[channel]); + return std::dynamic_pointer_cast>((*readers)[channel]); } template - static inline std::shared_ptr> CreateWriter( + static inline std::shared_ptr> CreateWriter( const std::string& channel) { return CHECK_NOTNULL(CurrentNode())->CreateWriter(channel); } @@ -72,8 +72,8 @@ class MonitorManager { apollo::common::monitor::MonitorLogBuffer log_buffer_; bool in_autonomous_driving_ = false; - std::shared_ptr node_; - std::unordered_map> + std::shared_ptr node_; + std::unordered_map> readers_; DECLARE_SINGLETON(MonitorManager); diff --git a/modules/monitor/common/recurrent_runner.cc b/modules/monitor/common/recurrent_runner.cc index dd506ffac75..5c2bf6ce2af 100644 --- a/modules/monitor/common/recurrent_runner.cc +++ b/modules/monitor/common/recurrent_runner.cc @@ -18,7 +18,7 @@ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/time/time.h" #include "modules/monitor/common/monitor_manager.h" diff --git a/modules/monitor/hardware/can/can_monitor.cc b/modules/monitor/hardware/can/can_monitor.cc index a9f1e92a9ce..5f88525fb31 100644 --- a/modules/monitor/hardware/can/can_monitor.cc +++ b/modules/monitor/hardware/can/can_monitor.cc @@ -18,7 +18,7 @@ #include "modules/canbus/common/canbus_gflags.h" #include "modules/canbus/proto/canbus_conf.pb.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/file.h" #include "modules/monitor/common/monitor_manager.h" #include "modules/monitor/hardware/can/can_checker_factory.h" diff --git a/modules/monitor/hardware/can/esdcan/esdcan_checker.cc b/modules/monitor/hardware/can/esdcan/esdcan_checker.cc index 8e3dc92d535..2b7a1df1aff 100644 --- a/modules/monitor/hardware/can/esdcan/esdcan_checker.cc +++ b/modules/monitor/hardware/can/esdcan/esdcan_checker.cc @@ -19,7 +19,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/string_util.h" #include "modules/monitor/hardware/can/esdcan/esdcan_err_str.h" diff --git a/modules/monitor/hardware/can/esdcan/esdcan_test.cc b/modules/monitor/hardware/can/esdcan/esdcan_test.cc index a3393a50ba4..e9bac27eed0 100644 --- a/modules/monitor/hardware/can/esdcan/esdcan_test.cc +++ b/modules/monitor/hardware/can/esdcan/esdcan_test.cc @@ -18,7 +18,7 @@ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/monitor/hardware/can/esdcan/esdcan_err_str.h" namespace apollo { diff --git a/modules/monitor/hardware/can/socketcan/socketcan_checker.cc b/modules/monitor/hardware/can/socketcan/socketcan_checker.cc index b1cadcfc1c1..1986c768fc6 100644 --- a/modules/monitor/hardware/can/socketcan/socketcan_checker.cc +++ b/modules/monitor/hardware/can/socketcan/socketcan_checker.cc @@ -20,7 +20,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/string_util.h" namespace apollo { diff --git a/modules/monitor/hardware/can/socketcan/socketcan_test.cc b/modules/monitor/hardware/can/socketcan/socketcan_test.cc index abdd2c4ace9..6a91d55ab73 100644 --- a/modules/monitor/hardware/can/socketcan/socketcan_test.cc +++ b/modules/monitor/hardware/can/socketcan/socketcan_test.cc @@ -16,7 +16,7 @@ #include "modules/monitor/hardware/can/socketcan/socketcan_test.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace monitor { diff --git a/modules/monitor/hardware/gps/BUILD b/modules/monitor/hardware/gps/BUILD index 74e315f29ca..379bbbf1a0c 100644 --- a/modules/monitor/hardware/gps/BUILD +++ b/modules/monitor/hardware/gps/BUILD @@ -7,7 +7,7 @@ cc_library( srcs = ["gps_monitor.cc"], hdrs = ["gps_monitor.h"], deps = [ - "//cybertron", + "//cyber", "//modules/drivers/gnss/proto:gnss_proto", "//modules/monitor/common:monitor_manager", "//modules/monitor/common:recurrent_runner", diff --git a/modules/monitor/hardware/gps/gps_monitor.cc b/modules/monitor/hardware/gps/gps_monitor.cc index 8789c2cf6d3..4d24cce5ab0 100644 --- a/modules/monitor/hardware/gps/gps_monitor.cc +++ b/modules/monitor/hardware/gps/gps_monitor.cc @@ -18,7 +18,7 @@ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/adapters/adapter_gflags.h" #include "modules/drivers/gnss/proto/gnss_best_pose.pb.h" #include "modules/drivers/gnss/proto/gnss_status.pb.h" diff --git a/modules/monitor/hardware/resource_monitor.cc b/modules/monitor/hardware/resource_monitor.cc index 52c8e0647ed..869e7a81d66 100644 --- a/modules/monitor/hardware/resource_monitor.cc +++ b/modules/monitor/hardware/resource_monitor.cc @@ -20,7 +20,7 @@ #include "boost/filesystem.hpp" #include "gflags/gflags.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/file.h" #include "modules/monitor/common/monitor_manager.h" diff --git a/modules/monitor/launch/monitor.launch b/modules/monitor/launch/monitor.launch index 9359f73d7ac..1a0a7df27dd 100644 --- a/modules/monitor/launch/monitor.launch +++ b/modules/monitor/launch/monitor.launch @@ -1,7 +1,7 @@ - + monitor /apollo/modules/monitor/dag/monitor.dag monitor - + diff --git a/modules/monitor/monitor.h b/modules/monitor/monitor.h index b822c0b0e4f..3c96a75c8f1 100644 --- a/modules/monitor/monitor.h +++ b/modules/monitor/monitor.h @@ -20,8 +20,8 @@ #include #include -#include "cybertron/component/timer_component.h" -#include "cybertron/cybertron.h" +#include "cyber/component/timer_component.h" +#include "cyber/cyber.h" #include "modules/monitor/common/recurrent_runner.h" #include "modules/monitor/proto/system_status.pb.h" @@ -32,7 +32,7 @@ namespace apollo { namespace monitor { -class Monitor : public apollo::cybertron::TimerComponent { +class Monitor : public apollo::cyber::TimerComponent { public: bool Init() override; bool Proc() override; @@ -40,7 +40,7 @@ class Monitor : public apollo::cybertron::TimerComponent { std::vector> runners_; }; -CYBERTRON_REGISTER_COMPONENT(Monitor) +CYBER_REGISTER_COMPONENT(Monitor) } // namespace monitor } // namespace apollo diff --git a/modules/monitor/reporters/static_info_reporter.cc b/modules/monitor/reporters/static_info_reporter.cc index 8b5708e6b6c..41c0bd74166 100644 --- a/modules/monitor/reporters/static_info_reporter.cc +++ b/modules/monitor/reporters/static_info_reporter.cc @@ -16,7 +16,7 @@ #include "modules/monitor/reporters/static_info_reporter.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "gflags/gflags.h" #include "modules/common/adapters/adapter_gflags.h" #include "modules/data/util/info_collector.h" diff --git a/modules/monitor/software/localization_monitor.cc b/modules/monitor/software/localization_monitor.cc index 32b88d2cc5b..7c642a2c78f 100644 --- a/modules/monitor/software/localization_monitor.cc +++ b/modules/monitor/software/localization_monitor.cc @@ -16,7 +16,7 @@ #include "modules/monitor/software/localization_monitor.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/adapters/adapter_gflags.h" #include "modules/common/util/map_util.h" #include "modules/localization/proto/localization.pb.h" diff --git a/modules/monitor/software/process_monitor.cc b/modules/monitor/software/process_monitor.cc index 26acf35b5a8..b0f56bd18f5 100644 --- a/modules/monitor/software/process_monitor.cc +++ b/modules/monitor/software/process_monitor.cc @@ -17,7 +17,7 @@ #include "modules/monitor/software/process_monitor.h" #include "gflags/gflags.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/file.h" #include "modules/common/util/string_util.h" #include "modules/monitor/common/monitor_manager.h" diff --git a/modules/monitor/software/safety_manager.cc b/modules/monitor/software/safety_manager.cc index 0e66bde8140..ef7a973c6f0 100644 --- a/modules/monitor/software/safety_manager.cc +++ b/modules/monitor/software/safety_manager.cc @@ -17,7 +17,7 @@ #include "modules/monitor/software/safety_manager.h" #include "modules/common/kv_db/kv_db.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/file.h" #include "modules/common/util/map_util.h" #include "modules/common/util/string_util.h" diff --git a/modules/monitor/software/summary_monitor.cc b/modules/monitor/software/summary_monitor.cc index e68c1be9c34..648feed6421 100644 --- a/modules/monitor/software/summary_monitor.cc +++ b/modules/monitor/software/summary_monitor.cc @@ -16,7 +16,7 @@ #include "modules/monitor/software/summary_monitor.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/adapters/adapter_gflags.h" #include "modules/common/util/string_util.h" #include "modules/monitor/common/monitor_manager.h" diff --git a/modules/monitor/software/topic_monitor.cc b/modules/monitor/software/topic_monitor.cc index 771fb639b39..26d5ffd1f8d 100644 --- a/modules/monitor/software/topic_monitor.cc +++ b/modules/monitor/software/topic_monitor.cc @@ -16,7 +16,7 @@ #include "modules/monitor/software/topic_monitor.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/adapters/adapter_gflags.h" #include "modules/common/util/string_util.h" #include "modules/control/proto/control_cmd.pb.h" @@ -35,7 +35,7 @@ DEFINE_double(topic_monitor_interval, 5, "Topic status checking interval (s)."); namespace apollo { namespace monitor { -std::shared_ptr TopicMonitor::CreateReaderFromChannel( +std::shared_ptr TopicMonitor::CreateReaderFromChannel( const std::string &channel) { if (channel == FLAGS_control_command_topic) { return MonitorManager::CreateReader( diff --git a/modules/monitor/software/topic_monitor.h b/modules/monitor/software/topic_monitor.h index 98dd4504f25..6805b5026d7 100644 --- a/modules/monitor/software/topic_monitor.h +++ b/modules/monitor/software/topic_monitor.h @@ -18,7 +18,7 @@ #include #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/monitor/common/recurrent_runner.h" #include "modules/monitor/proto/monitor_conf.pb.h" @@ -30,13 +30,13 @@ class TopicMonitor : public RecurrentRunner { TopicMonitor(const TopicConf &config, TopicStatus *status); void RunOnce(const double current_time) override; - static std::shared_ptr CreateReaderFromChannel( + static std::shared_ptr CreateReaderFromChannel( const std::string& channel); private: const TopicConf &config_; TopicStatus *status_; - std::shared_ptr reader_; + std::shared_ptr reader_; }; } // namespace monitor diff --git a/modules/perception/base/BUILD b/modules/perception/base/BUILD index e76ac370c2b..2baefaef270 100644 --- a/modules/perception/base/BUILD +++ b/modules/perception/base/BUILD @@ -45,7 +45,7 @@ cc_library( "blob.h", ], deps = [ - "//cybertron", + "//cyber", ":common", ":syncedmem", ], @@ -145,7 +145,7 @@ cc_library( ], deps = [ ":camera", - "//cybertron", + "//cyber", "@eigen", ], ) @@ -206,7 +206,7 @@ cc_library( "impending_collision_edge.h", ], deps = [ - "//cybertron", + "//cyber", "@eigen", ], ) @@ -277,7 +277,7 @@ cc_test( ":object_pool", ":object_pool_types", ":point_cloud", - "//cybertron", + "//cyber", "@eigen", "@gtest//:main", ], @@ -296,7 +296,7 @@ cc_library( ":object", ":object_pool", ":point_cloud", - "//cybertron", + "//cyber", "@eigen", ], ) @@ -313,7 +313,7 @@ cc_library( ":camera", ":distortion_model", ":polynomial", - "//cybertron", + "//cyber", "@eigen", ], ) @@ -387,7 +387,7 @@ cc_library( ], deps = [ ":common", - "//cybertron", + "//cyber", ], ) diff --git a/modules/perception/base/blob.h b/modules/perception/base/blob.h index 9854059ae6d..cef2e09a0ac 100644 --- a/modules/perception/base/blob.h +++ b/modules/perception/base/blob.h @@ -66,7 +66,7 @@ license and copyright terms herein. #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/base/syncedmem.h" namespace apollo { diff --git a/modules/perception/base/distortion_model.cc b/modules/perception/base/distortion_model.cc index bd898a3e354..3849bd54752 100644 --- a/modules/perception/base/distortion_model.cc +++ b/modules/perception/base/distortion_model.cc @@ -17,7 +17,7 @@ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace perception { diff --git a/modules/perception/base/object_pool_types.cc b/modules/perception/base/object_pool_types.cc index 7dd0bfd5220..b88a9d78526 100644 --- a/modules/perception/base/object_pool_types.cc +++ b/modules/perception/base/object_pool_types.cc @@ -15,7 +15,7 @@ *****************************************************************************/ #include "modules/perception/base/object_pool_types.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace perception { diff --git a/modules/perception/base/omnidirectional_model.cc b/modules/perception/base/omnidirectional_model.cc index 6667d1324af..a7effa33059 100644 --- a/modules/perception/base/omnidirectional_model.cc +++ b/modules/perception/base/omnidirectional_model.cc @@ -18,7 +18,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/base/camera.h" #include "modules/perception/base/polynomial.h" diff --git a/modules/perception/base/options_define.h b/modules/perception/base/options_define.h index 12684fb5fca..395378d8d7d 100644 --- a/modules/perception/base/options_define.h +++ b/modules/perception/base/options_define.h @@ -18,5 +18,5 @@ // build perception with cpu or gpu /* #undef PERCEPTION_CPU_ONLY */ -// build perception with using cybertron log lib or glog lib -/* #undef PERCEPTION_USE_CYBERTRON */ +// build perception with using cyber log lib or glog lib +/* #undef PERCEPTION_USE_CYBER */ diff --git a/modules/perception/base/options_define.h.in b/modules/perception/base/options_define.h.in index eb00efd8ba3..1766b5bc2d5 100644 --- a/modules/perception/base/options_define.h.in +++ b/modules/perception/base/options_define.h.in @@ -19,7 +19,7 @@ // build perception with cpu or gpu #cmakedefine PERCEPTION_CPU_ONLY -// build perception with using cybertron log lib or glog lib -#cmakedefine PERCEPTION_USE_CYBERTRON +// build perception with using cyber log lib or glog lib +#cmakedefine PERCEPTION_USE_CYBER diff --git a/modules/perception/base/syncedmem.h b/modules/perception/base/syncedmem.h index c14be61603d..83adb544b34 100644 --- a/modules/perception/base/syncedmem.h +++ b/modules/perception/base/syncedmem.h @@ -65,7 +65,7 @@ license and copyright terms herein. #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/base/common.h" namespace apollo { diff --git a/modules/perception/camera/app/BUILD b/modules/perception/camera/app/BUILD index c9005d76403..d79ef74c0df 100644 --- a/modules/perception/camera/app/BUILD +++ b/modules/perception/camera/app/BUILD @@ -25,7 +25,7 @@ cc_library( "debug_info.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/perception/base:base", "//modules/perception/camera/common:common", "//modules/perception/camera/lib/interface:interface", @@ -45,7 +45,7 @@ cc_library( ":camera_app_lib_proto", "@yaml_cpp//:yaml", "//external:gflags", - "//cybertron", + "//cyber", "//modules/common/util:file_util", "//modules/perception/base:base", "//modules/perception/camera/common:common", @@ -80,7 +80,7 @@ cc_library( ], deps = [ ":camera_app_lib_proto", - "//cybertron", + "//cyber", "//modules/common/util:file_util", "//modules/perception/camera/common:common", "//modules/perception/camera/lib/interface:interface", diff --git a/modules/perception/camera/app/debug_info.cc b/modules/perception/camera/app/debug_info.cc index c5c5a94534a..23130204136 100644 --- a/modules/perception/camera/app/debug_info.cc +++ b/modules/perception/camera/app/debug_info.cc @@ -15,7 +15,7 @@ *****************************************************************************/ #include "modules/perception/camera/app/debug_info.h" #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace perception { diff --git a/modules/perception/camera/app/obstacle_camera_perception.cc b/modules/perception/camera/app/obstacle_camera_perception.cc index 564150cf67e..dc82bdde34b 100644 --- a/modules/perception/camera/app/obstacle_camera_perception.cc +++ b/modules/perception/camera/app/obstacle_camera_perception.cc @@ -21,7 +21,7 @@ #include #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/file.h" #include "modules/perception/base/object.h" #include "modules/perception/camera/app/debug_info.h" @@ -40,8 +40,8 @@ namespace camera { bool ObstacleCameraPerception::Init( const CameraPerceptionInitOptions &options) { std::string work_root = ""; - if (options.use_cybertron_work_root) { - GetCybertronWorkRoot(&work_root); + if (options.use_cyber_work_root) { + GetCyberWorkRoot(&work_root); } std::string config_file = lib::FileUtil::GetAbsolutePath(options.root_dir, diff --git a/modules/perception/camera/app/traffic_light_camera_perception.cc b/modules/perception/camera/app/traffic_light_camera_perception.cc index 5d85b82f5fd..b5cafb99582 100644 --- a/modules/perception/camera/app/traffic_light_camera_perception.cc +++ b/modules/perception/camera/app/traffic_light_camera_perception.cc @@ -18,7 +18,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/file.h" #include "modules/perception/camera/common/util.h" #include "modules/perception/camera/lib/traffic_light/detector/detection/detection.h" @@ -34,8 +34,8 @@ namespace camera { bool TrafficLightCameraPerception::Init( const CameraPerceptionInitOptions &options) { std::string work_root = ""; - if (options.use_cybertron_work_root) { - GetCybertronWorkRoot(&work_root); + if (options.use_cyber_work_root) { + GetCyberWorkRoot(&work_root); } std::string proto_path = lib::FileUtil::GetAbsolutePath(options.root_dir, options.conf_file); diff --git a/modules/perception/camera/common/BUILD b/modules/perception/camera/common/BUILD index 2df101184bd..167125c53eb 100644 --- a/modules/perception/camera/common/BUILD +++ b/modules/perception/camera/common/BUILD @@ -74,7 +74,7 @@ cc_library( ], deps = [ "//external:gflags", - "//cybertron", + "//cyber", "//modules/common/util:file_util", "//modules/perception/base:base", "//modules/perception/camera/common/proto:object_template_meta_schema_proto", diff --git a/modules/perception/camera/common/camera_ground_plane.cc b/modules/perception/camera/common/camera_ground_plane.cc index 2178d9c45cb..7522a8f9e7b 100644 --- a/modules/perception/camera/common/camera_ground_plane.cc +++ b/modules/perception/camera/common/camera_ground_plane.cc @@ -18,7 +18,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/common/i_lib/da/i_ransac.h" #include "modules/perception/common/i_lib/geometry/i_util.h" diff --git a/modules/perception/camera/common/camera_ground_plane.h b/modules/perception/camera/common/camera_ground_plane.h index 8a6fa4c2bfd..eccda86ef1f 100644 --- a/modules/perception/camera/common/camera_ground_plane.h +++ b/modules/perception/camera/common/camera_ground_plane.h @@ -17,7 +17,7 @@ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/common/i_lib/core/i_blas.h" #include "modules/perception/common/i_lib/geometry/i_line.h" diff --git a/modules/perception/camera/common/data_provider.cc b/modules/perception/camera/common/data_provider.cc index 2ad7b495b14..1a39e7032b4 100644 --- a/modules/perception/camera/common/data_provider.cc +++ b/modules/perception/camera/common/data_provider.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ #include "modules/perception/camera/common/data_provider.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace perception { diff --git a/modules/perception/camera/common/object_template_manager.cc b/modules/perception/camera/common/object_template_manager.cc index 5fdc90d5dea..801e6338b7b 100644 --- a/modules/perception/camera/common/object_template_manager.cc +++ b/modules/perception/camera/common/object_template_manager.cc @@ -23,7 +23,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/file.h" #include "modules/perception/common/io/io_util.h" #include "modules/perception/lib/config_manager/config_manager.h" diff --git a/modules/perception/camera/common/object_template_manager.h b/modules/perception/camera/common/object_template_manager.h index 8518e8b571c..475d62259d9 100644 --- a/modules/perception/camera/common/object_template_manager.h +++ b/modules/perception/camera/common/object_template_manager.h @@ -25,7 +25,7 @@ #include #include "gflags/gflags.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/base/object_types.h" #include "modules/perception/camera/common/proto/object_template_meta_schema.pb.h" #include "modules/perception/lib/singleton/singleton.h" @@ -48,7 +48,7 @@ struct ObjectTemplateManagerInitOptions { std::string root_dir; std::string conf_file; int gpu_id = 0; - bool use_cybertron_work_root = false; + bool use_cyber_work_root = false; }; class ObjectTemplateManager { diff --git a/modules/perception/camera/common/twod_threed_util.h b/modules/perception/camera/common/twod_threed_util.h index a811c2c4b01..45b99538d98 100644 --- a/modules/perception/camera/common/twod_threed_util.h +++ b/modules/perception/camera/common/twod_threed_util.h @@ -22,7 +22,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/common/i_lib/core/i_constant.h" #include "modules/perception/common/i_lib/geometry/i_util.h" #include "modules/perception/common/i_lib/geometry/i_line.h" diff --git a/modules/perception/camera/common/undistortion_handler.cc b/modules/perception/camera/common/undistortion_handler.cc index 398d98239b3..d24355b0889 100644 --- a/modules/perception/camera/common/undistortion_handler.cc +++ b/modules/perception/camera/common/undistortion_handler.cc @@ -22,7 +22,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/common/sensor_manager/sensor_manager.h" namespace apollo { diff --git a/modules/perception/camera/common/util.cc b/modules/perception/camera/common/util.cc index 04ad5dc4973..be65eb990f2 100644 --- a/modules/perception/camera/common/util.cc +++ b/modules/perception/camera/common/util.cc @@ -15,7 +15,7 @@ *****************************************************************************/ #include "modules/perception/camera/common/util.h" #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace perception { @@ -149,14 +149,14 @@ bool ResizeCPU(const base::Blob &src_blob, return true; } -void GetCybertronWorkRoot(std::string* work_root) { +void GetCyberWorkRoot(std::string* work_root) { char *var = nullptr; var = std::getenv("MODULE_PATH"); if (var != nullptr) { *work_root = std::string(var); return; } - var = std::getenv("CYBERTRON_PATH"); + var = std::getenv("CYBER_PATH"); if (var != nullptr) { *work_root = std::string(var); return; diff --git a/modules/perception/camera/common/util.h b/modules/perception/camera/common/util.h index 46b70c553dd..818e5b10bdd 100644 --- a/modules/perception/camera/common/util.h +++ b/modules/perception/camera/common/util.h @@ -29,7 +29,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/base/blob.h" #include "modules/perception/base/image.h" #include "modules/perception/base/object.h" @@ -152,7 +152,7 @@ bool ResizeCPU(const base::Blob &src_gpu, std::shared_ptr> dst, int stepwidth, int start_axis); -void GetCybertronWorkRoot(std::string *work_root); +void GetCyberWorkRoot(std::string *work_root); void FillObjectPolygonFromBBox3D(base::Object *object_ptr); template diff --git a/modules/perception/camera/lib/calibrator/common/BUILD b/modules/perception/camera/lib/calibrator/common/BUILD index 91bd8267fe8..16b377c26ce 100644 --- a/modules/perception/camera/lib/calibrator/common/BUILD +++ b/modules/perception/camera/lib/calibrator/common/BUILD @@ -13,7 +13,7 @@ cc_library( ], deps = [ "@eigen", - "//cybertron", + "//cyber", "//modules/perception/common/i_lib/core:core", ], ) diff --git a/modules/perception/camera/lib/calibrator/common/histogram_estimator.h b/modules/perception/camera/lib/calibrator/common/histogram_estimator.h index c2c2ed09c02..ad8c67b51b0 100644 --- a/modules/perception/camera/lib/calibrator/common/histogram_estimator.h +++ b/modules/perception/camera/lib/calibrator/common/histogram_estimator.h @@ -21,7 +21,7 @@ #include #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace perception { diff --git a/modules/perception/camera/lib/feature_extractor/tfe/project_feature.cc b/modules/perception/camera/lib/feature_extractor/tfe/project_feature.cc index d311ce976d5..bbedd94305b 100644 --- a/modules/perception/camera/lib/feature_extractor/tfe/project_feature.cc +++ b/modules/perception/camera/lib/feature_extractor/tfe/project_feature.cc @@ -18,7 +18,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/file.h" #include "modules/perception/camera/common/global_config.h" #include "modules/perception/inference/inference_factory.h" diff --git a/modules/perception/camera/lib/interface/base_init_options.h b/modules/perception/camera/lib/interface/base_init_options.h index 1387b133469..9f509c12f6a 100644 --- a/modules/perception/camera/lib/interface/base_init_options.h +++ b/modules/perception/camera/lib/interface/base_init_options.h @@ -25,7 +25,7 @@ struct BaseInitOptions { std::string root_dir; std::string conf_file; int gpu_id = 0; - bool use_cybertron_work_root = false; + bool use_cyber_work_root = false; }; } // namespace camera diff --git a/modules/perception/camera/lib/lane/common/BUILD b/modules/perception/camera/lib/lane/common/BUILD index 4c470f1784b..6796cd4e94e 100644 --- a/modules/perception/camera/lib/lane/common/BUILD +++ b/modules/perception/camera/lib/lane/common/BUILD @@ -28,7 +28,7 @@ cc_library( ], deps = [ "@eigen", - "//cybertron", + "//cyber", "//modules/perception/base:base", ], ) diff --git a/modules/perception/camera/lib/lane/common/common_functions.h b/modules/perception/camera/lib/lane/common/common_functions.h index 79b77cf128f..63feb54f033 100644 --- a/modules/perception/camera/lib/lane/common/common_functions.h +++ b/modules/perception/camera/lib/lane/common/common_functions.h @@ -19,7 +19,7 @@ #include #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/base/box.h" #include "modules/perception/base/point.h" diff --git a/modules/perception/camera/lib/lane/postprocessor/denseline/BUILD b/modules/perception/camera/lib/lane/postprocessor/denseline/BUILD index a9afa67eff1..b1013ebfb30 100644 --- a/modules/perception/camera/lib/lane/postprocessor/denseline/BUILD +++ b/modules/perception/camera/lib/lane/postprocessor/denseline/BUILD @@ -28,7 +28,7 @@ cc_library( ], deps = [ - "//cybertron", + "//cyber", ":denseline_postprocessor_proto", "//modules/common/util:file_util", "//modules/perception/base:base", diff --git a/modules/perception/camera/lib/lane/postprocessor/denseline/denseline_lane_postprocessor.cc b/modules/perception/camera/lib/lane/postprocessor/denseline/denseline_lane_postprocessor.cc index 9610da0c280..66e74aba1e5 100644 --- a/modules/perception/camera/lib/lane/postprocessor/denseline/denseline_lane_postprocessor.cc +++ b/modules/perception/camera/lib/lane/postprocessor/denseline/denseline_lane_postprocessor.cc @@ -19,7 +19,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/file.h" #include "modules/perception/base/object_types.h" #include "modules/perception/camera/common/math_functions.h" diff --git a/modules/perception/camera/lib/obstacle/detector/yolo/BUILD b/modules/perception/camera/lib/obstacle/detector/yolo/BUILD index d60d3f2a158..19dfdfec690 100644 --- a/modules/perception/camera/lib/obstacle/detector/yolo/BUILD +++ b/modules/perception/camera/lib/obstacle/detector/yolo/BUILD @@ -32,7 +32,7 @@ cc_library( "region_output.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/perception/base:base", "//modules/perception/camera/common:common", "//modules/perception/camera/lib/obstacle/detector/yolo/proto:yolo_proto", diff --git a/modules/perception/camera/lib/obstacle/detector/yolo/region_output.cc b/modules/perception/camera/lib/obstacle/detector/yolo/region_output.cc index d375631bf7e..fb1fbdde052 100644 --- a/modules/perception/camera/lib/obstacle/detector/yolo/region_output.cc +++ b/modules/perception/camera/lib/obstacle/detector/yolo/region_output.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/camera/lib/obstacle/detector/yolo/region_output.h" namespace apollo { diff --git a/modules/perception/camera/lib/obstacle/detector/yolo/yolo_obstacle_detector.cc b/modules/perception/camera/lib/obstacle/detector/yolo/yolo_obstacle_detector.cc index e78e1599892..aa555e2a08b 100644 --- a/modules/perception/camera/lib/obstacle/detector/yolo/yolo_obstacle_detector.cc +++ b/modules/perception/camera/lib/obstacle/detector/yolo/yolo_obstacle_detector.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ #include "modules/perception/camera/lib/obstacle/detector/yolo/yolo_obstacle_detector.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/base/common.h" #include "modules/perception/camera/common/timer.h" #include "modules/perception/inference/inference_factory.h" diff --git a/modules/perception/camera/lib/obstacle/postprocessor/location_refiner/BUILD b/modules/perception/camera/lib/obstacle/postprocessor/location_refiner/BUILD index e9129f1045d..35fa232f01b 100644 --- a/modules/perception/camera/lib/obstacle/postprocessor/location_refiner/BUILD +++ b/modules/perception/camera/lib/obstacle/postprocessor/location_refiner/BUILD @@ -29,7 +29,7 @@ cc_library( deps = [ ":obj_postprocessor", ":location_refiner_proto", - "//cybertron", + "//cyber", "//modules/common/util:file_util", "//modules/perception/camera/common:common", "//modules/perception/camera/lib/interface:interface", diff --git a/modules/perception/camera/lib/obstacle/postprocessor/location_refiner/location_refiner_obstacle_postprocessor.cc b/modules/perception/camera/lib/obstacle/postprocessor/location_refiner/location_refiner_obstacle_postprocessor.cc index 50a334af523..b23e6a03d8e 100644 --- a/modules/perception/camera/lib/obstacle/postprocessor/location_refiner/location_refiner_obstacle_postprocessor.cc +++ b/modules/perception/camera/lib/obstacle/postprocessor/location_refiner/location_refiner_obstacle_postprocessor.cc @@ -18,7 +18,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/file.h" #include "modules/perception/camera/common/global_config.h" #include "modules/perception/camera/lib/interface/base_calibration_service.h" diff --git a/modules/perception/camera/lib/obstacle/tracker/common/BUILD b/modules/perception/camera/lib/obstacle/tracker/common/BUILD index 7ce0a5d7e0f..0830b3a5d09 100644 --- a/modules/perception/camera/lib/obstacle/tracker/common/BUILD +++ b/modules/perception/camera/lib/obstacle/tracker/common/BUILD @@ -13,7 +13,7 @@ cuda_library( ], deps = [ "@cuda", - "//cybertron", + "//cyber", "//modules/perception/camera/common:camera_frame", "//modules/perception/inference/utils:inference_gemm_lib", ], @@ -58,7 +58,7 @@ cc_library( ], deps = [ "@eigen", - "//cybertron", + "//cyber", ], ) diff --git a/modules/perception/camera/lib/obstacle/tracker/common/kalman_filter.cc b/modules/perception/camera/lib/obstacle/tracker/common/kalman_filter.cc index 069fe03c482..3bca72f07f0 100644 --- a/modules/perception/camera/lib/obstacle/tracker/common/kalman_filter.cc +++ b/modules/perception/camera/lib/obstacle/tracker/common/kalman_filter.cc @@ -16,7 +16,7 @@ #include "modules/perception/camera/lib/obstacle/tracker/common/kalman_filter.h" #include #include "Eigen/LU" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace perception { diff --git a/modules/perception/camera/lib/obstacle/tracker/common/similar.cu b/modules/perception/camera/lib/obstacle/tracker/common/similar.cu index 4086bb1b69c..643c0afc8d0 100644 --- a/modules/perception/camera/lib/obstacle/tracker/common/similar.cu +++ b/modules/perception/camera/lib/obstacle/tracker/common/similar.cu @@ -18,7 +18,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/camera/common/util.h" #include "modules/perception/inference/utils/gemm.h" diff --git a/modules/perception/camera/lib/obstacle/tracker/omt/BUILD b/modules/perception/camera/lib/obstacle/tracker/omt/BUILD index 37218c36934..4a089b6110f 100644 --- a/modules/perception/camera/lib/obstacle/tracker/omt/BUILD +++ b/modules/perception/camera/lib/obstacle/tracker/omt/BUILD @@ -58,7 +58,7 @@ cc_library( "frame_list.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/perception/camera/common:common", "//modules/perception/camera/lib/interface:interface", "//modules/perception/inference/utils:inference_cuda_util_lib", @@ -99,7 +99,7 @@ cc_library( ":frame_list", ":omt_proto", ":target", - "//cybertron", + "//cyber", "//modules/perception/camera/common:common", "//modules/perception/camera/lib/interface:interface", ], diff --git a/modules/perception/camera/lib/obstacle/tracker/omt/frame_list.h b/modules/perception/camera/lib/obstacle/tracker/omt/frame_list.h index d17a65eec20..3c1b27d4436 100644 --- a/modules/perception/camera/lib/obstacle/tracker/omt/frame_list.h +++ b/modules/perception/camera/lib/obstacle/tracker/omt/frame_list.h @@ -19,7 +19,7 @@ #include #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/inference/utils/util.h" #include "modules/perception/inference/utils/cuda_util.h" #include "modules/perception/camera/common/camera_frame.h" diff --git a/modules/perception/camera/lib/obstacle/tracker/omt/obstacle_reference.cc b/modules/perception/camera/lib/obstacle/tracker/omt/obstacle_reference.cc index f1f49069c49..45f748b0c8c 100644 --- a/modules/perception/camera/lib/obstacle/tracker/omt/obstacle_reference.cc +++ b/modules/perception/camera/lib/obstacle/tracker/omt/obstacle_reference.cc @@ -19,7 +19,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/camera/common/util.h" #include "modules/perception/camera/lib/interface/base_calibration_service.h" diff --git a/modules/perception/camera/lib/obstacle/tracker/omt/target.cc b/modules/perception/camera/lib/obstacle/tracker/omt/target.cc index 1ca41338240..13e21887f44 100644 --- a/modules/perception/camera/lib/obstacle/tracker/omt/target.cc +++ b/modules/perception/camera/lib/obstacle/tracker/omt/target.cc @@ -20,7 +20,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/camera/common/math_functions.h" #include "modules/perception/camera/common/util.h" #include "modules/perception/common/geometry/basic.h" diff --git a/modules/perception/camera/lib/obstacle/transformer/multicue/BUILD b/modules/perception/camera/lib/obstacle/transformer/multicue/BUILD index f59563656ee..d73ec0f8e12 100644 --- a/modules/perception/camera/lib/obstacle/transformer/multicue/BUILD +++ b/modules/perception/camera/lib/obstacle/transformer/multicue/BUILD @@ -27,7 +27,7 @@ cc_library( "obj_mapper.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/perception/camera/common:common", ], ) @@ -43,7 +43,7 @@ cc_library( deps = [ ":multicue_proto", ":obj_mapper", - "//cybertron", + "//cyber", "//modules/common/util:file_util", "//modules/perception/camera/common:common", "//modules/perception/camera/lib/interface:interface", diff --git a/modules/perception/camera/lib/obstacle/transformer/multicue/multicue_obstacle_transformer.cc b/modules/perception/camera/lib/obstacle/transformer/multicue/multicue_obstacle_transformer.cc index 5158caefcb2..3f8055f6766 100644 --- a/modules/perception/camera/lib/obstacle/transformer/multicue/multicue_obstacle_transformer.cc +++ b/modules/perception/camera/lib/obstacle/transformer/multicue/multicue_obstacle_transformer.cc @@ -15,7 +15,7 @@ *****************************************************************************/ #include "modules/perception/camera/lib/obstacle/transformer/multicue/multicue_obstacle_transformer.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/file.h" #include "modules/perception/camera/common/global_config.h" #include "modules/perception/lib/io/file_util.h" diff --git a/modules/perception/camera/lib/obstacle/transformer/multicue/obj_mapper.h b/modules/perception/camera/lib/obstacle/transformer/multicue/obj_mapper.h index 203eefc149b..ff224f8ea55 100644 --- a/modules/perception/camera/lib/obstacle/transformer/multicue/obj_mapper.h +++ b/modules/perception/camera/lib/obstacle/transformer/multicue/obj_mapper.h @@ -19,7 +19,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/camera/common/object_template_manager.h" #include "modules/perception/camera/common/twod_threed_util.h" diff --git a/modules/perception/camera/lib/traffic_light/detector/detection/BUILD b/modules/perception/camera/lib/traffic_light/detector/detection/BUILD index ac2c82e4b2e..f56744aba38 100644 --- a/modules/perception/camera/lib/traffic_light/detector/detection/BUILD +++ b/modules/perception/camera/lib/traffic_light/detector/detection/BUILD @@ -29,7 +29,7 @@ cc_library( ":cropbox", ":select", ":trafficlight_detector_detection_proto", - "//cybertron", + "//cyber", "//modules/common/util:file_util", "//modules/perception/base:base", "//modules/perception/camera/common:common", @@ -51,7 +51,7 @@ cc_library( "select.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/perception/base:base", "//modules/perception/camera/common:common", "//modules/perception/common/graph:hungarian_optimizer", diff --git a/modules/perception/camera/lib/traffic_light/detector/detection/detection.cc b/modules/perception/camera/lib/traffic_light/detector/detection/detection.cc index 111cc68572b..235717149e4 100644 --- a/modules/perception/camera/lib/traffic_light/detector/detection/detection.cc +++ b/modules/perception/camera/lib/traffic_light/detector/detection/detection.cc @@ -21,7 +21,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/file.h" #include "modules/perception/lib/io/file_util.h" #include "modules/perception/camera/common/util.h" diff --git a/modules/perception/camera/lib/traffic_light/detector/detection/select.cc b/modules/perception/camera/lib/traffic_light/detector/detection/select.cc index 37359c7aff8..1003ff8cd11 100644 --- a/modules/perception/camera/lib/traffic_light/detector/detection/select.cc +++ b/modules/perception/camera/lib/traffic_light/detector/detection/select.cc @@ -18,7 +18,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace perception { diff --git a/modules/perception/camera/lib/traffic_light/preprocessor/BUILD b/modules/perception/camera/lib/traffic_light/preprocessor/BUILD index add3b972ac2..ce72dbb061e 100644 --- a/modules/perception/camera/lib/traffic_light/preprocessor/BUILD +++ b/modules/perception/camera/lib/traffic_light/preprocessor/BUILD @@ -28,7 +28,7 @@ cc_library( ], deps = [ ":pose", - "//cybertron", + "//cyber", "//modules/common/util:file_util", "//modules/perception/base:base", "//modules/perception/camera/common:common", @@ -48,7 +48,7 @@ cc_library( "pose.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/perception/base:base", ], ) @@ -71,7 +71,7 @@ cc_library( "@eigen", ":multi_camera_projection", "//external:gflags", - "//cybertron", + "//cyber", "//modules/perception/base:base", "//modules/perception/camera/common:common", "//modules/perception/camera/lib/interface:interface", diff --git a/modules/perception/camera/lib/traffic_light/preprocessor/multi_camera_projection.cc b/modules/perception/camera/lib/traffic_light/preprocessor/multi_camera_projection.cc index f08abbf25d9..7f0ea177332 100644 --- a/modules/perception/camera/lib/traffic_light/preprocessor/multi_camera_projection.cc +++ b/modules/perception/camera/lib/traffic_light/preprocessor/multi_camera_projection.cc @@ -24,7 +24,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/file.h" #include "modules/perception/common/sensor_manager/sensor_manager.h" #include "modules/perception/lib/io/file_util.h" diff --git a/modules/perception/camera/lib/traffic_light/preprocessor/pose.cc b/modules/perception/camera/lib/traffic_light/preprocessor/pose.cc index 142a3d8aa70..ee6faf8b452 100644 --- a/modules/perception/camera/lib/traffic_light/preprocessor/pose.cc +++ b/modules/perception/camera/lib/traffic_light/preprocessor/pose.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ #include "modules/perception/camera/lib/traffic_light/preprocessor/pose.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace perception { diff --git a/modules/perception/camera/lib/traffic_light/preprocessor/tl_preprocessor.cc b/modules/perception/camera/lib/traffic_light/preprocessor/tl_preprocessor.cc index 7358b8c69eb..7ed942c6519 100644 --- a/modules/perception/camera/lib/traffic_light/preprocessor/tl_preprocessor.cc +++ b/modules/perception/camera/lib/traffic_light/preprocessor/tl_preprocessor.cc @@ -17,7 +17,7 @@ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/file.h" #include "modules/perception/camera/common/util.h" #include "modules/perception/lib/config_manager/config_manager.h" diff --git a/modules/perception/camera/test/BUILD b/modules/perception/camera/test/BUILD index 18e5df0ff24..8dc3f20d001 100644 --- a/modules/perception/camera/test/BUILD +++ b/modules/perception/camera/test/BUILD @@ -219,7 +219,7 @@ # "camera_lib_calibration_service_online_calibration_service_test.cc", # ], # deps = [ -# "//cybertron", +# "//cyber", # "//modules/perception/base:base", # "//modules/perception/camera/lib/calibration_service/online_calibration_service:online_calibration_service", # "//modules/perception/camera/lib/calibrator/laneline:laneline_calibrator", @@ -364,7 +364,7 @@ # "-lopencv_highgui", # ], # deps = [ -# "//cybertron", +# "//cyber", # "//modules/perception/camera/lib/lane/common:common_functions", # "//modules/perception/base:base", # "//modules/perception/common/io:io_util", @@ -385,7 +385,7 @@ # "-lopencv_highgui", # ], # deps = [ -# "//cybertron", +# "//cyber", # "//modules/perception/camera/lib/lane/detector/denseline:denseline_lane_detector", # "//modules/perception/base:base", # "//modules/perception/common/io:io_util", @@ -404,7 +404,7 @@ # "-lopencv_highgui", # ], # deps = [ -# "//cybertron", +# "//cyber", # "//modules/perception/camera/common:common", # "//modules/perception/camera/lib/lane/detector/denseline:denseline_lane_detector", # "//modules/perception/camera/lib/lane/postprocessor/denseline:denseline_lane_postprocessor", @@ -458,7 +458,7 @@ # "camera_lib_obstacle_postprocessor_location_refiner_test.cc", # ], # deps = [ -# "//cybertron", +# "//cyber", # "//modules/perception/camera/lib/obstacle/postprocessor/location_refiner:location_refiner_obstacle_postprocessor", # "//modules/perception/camera/lib/calibration_service/online_calibration_service:online_calibration_service", # "//modules/perception/camera/lib/calibrator/laneline:laneline_calibrator", @@ -474,7 +474,7 @@ # ], # deps = [ # "@eigen", -# "//cybertron", +# "//cyber", # "//modules/perception/camera/common:common", # "//modules/perception/camera/lib/obstacle/tracker/common:common", # "//modules/perception/inference/utils:inference_util_lib", @@ -510,7 +510,7 @@ # # "-lopencv_highgui", # # ], # # deps = [ -# # "//cybertron", +# # "//cyber", # # "//modules/perception/base:base", # # "//modules/perception/camera/common:common", # # "//modules/perception/camera/lib/interface:interface", @@ -712,7 +712,7 @@ # "-lcaffe", # ], # deps = [ -# "//cybertron", +# "//cyber", # "//modules/perception/base:distortion_model", # "//modules/perception/common/io:io_util", # "//modules/perception/camera/lib/traffic_light/tracker:semantic_decision", diff --git a/modules/perception/camera/test/camera_app_obstacle_camera_perception_test.cc b/modules/perception/camera/test/camera_app_obstacle_camera_perception_test.cc index fafa1b80af0..e88560fdeb9 100644 --- a/modules/perception/camera/test/camera_app_obstacle_camera_perception_test.cc +++ b/modules/perception/camera/test/camera_app_obstacle_camera_perception_test.cc @@ -29,7 +29,7 @@ DECLARE_string(obs_sensor_intrinsic_path); namespace camera { TEST(ObstacleCameraPerceptionTest, init_all_test) { unsetenv("MODULE_PATH"); - unsetenv("CYBERTRON_PATH"); + unsetenv("CYBER_PATH"); FLAGS_obs_sensor_intrinsic_path = "/apollo/modules/perception/testdata/" "camera/app/data/perception/camera/params"; @@ -48,7 +48,7 @@ TEST(ObstacleCameraPerceptionTest, init_all_test) { TEST(ObstacleCameraPerceptionTest, init_feature_extractor_test) { unsetenv("MODULE_PATH"); - unsetenv("CYBERTRON_PATH"); + unsetenv("CYBER_PATH"); FLAGS_obs_sensor_meta_path = "/apollo/modules/perception/testdata/" "camera/app/data/perception/camera/sensor_meta_camera.pt"; ObstacleCameraPerception perception; @@ -61,7 +61,7 @@ TEST(ObstacleCameraPerceptionTest, init_feature_extractor_test) { TEST(ObstacleCameraPerceptionTest, init_debug_para_test) { unsetenv("MODULE_PATH"); - unsetenv("CYBERTRON_PATH"); + unsetenv("CYBER_PATH"); FLAGS_obs_sensor_meta_path = "/apollo/modules/perception/testdata/" "camera/app/data/perception/camera/sensor_meta_camera.pt"; ObstacleCameraPerception perception; @@ -74,7 +74,7 @@ TEST(ObstacleCameraPerceptionTest, init_debug_para_test) { TEST(ObstacleCameraPerceptionTest, perception_test) { unsetenv("MODULE_PATH"); - unsetenv("CYBERTRON_PATH"); + unsetenv("CYBER_PATH"); FLAGS_obs_sensor_meta_path = "/apollo/modules/perception/testdata/" "camera/app/data/perception/camera/sensor_meta_camera.pt"; ObstacleCameraPerception perception; diff --git a/modules/perception/camera/test/camera_app_traffic_light_camera_perception_test.cc b/modules/perception/camera/test/camera_app_traffic_light_camera_perception_test.cc index 9dcd8c872d8..15b4cdb4c4a 100644 --- a/modules/perception/camera/test/camera_app_traffic_light_camera_perception_test.cc +++ b/modules/perception/camera/test/camera_app_traffic_light_camera_perception_test.cc @@ -31,7 +31,7 @@ namespace camera { TEST(TrafficLightCameraPerceptionTest, normal) { unsetenv("MODULE_PATH"); - unsetenv("CYBERTRON_PATH"); + unsetenv("CYBER_PATH"); fLS::FLAGS_obs_sensor_meta_path = "/apollo/modules/perception/testdata/" "camera/app/data/perception/camera/sensor_meta_camera.pt"; FLAGS_obs_sensor_intrinsic_path = "/apollo/modules/perception/testdata/" @@ -86,7 +86,7 @@ TEST(TrafficLightCameraPerceptionTest, normal) { TEST(TrafficLightCameraPerceptionTest, bad_proto) { unsetenv("MODULE_PATH"); - unsetenv("CYBERTRON_PATH"); + unsetenv("CYBER_PATH"); fLS::FLAGS_obs_sensor_meta_path = "/apollo/modules/perception/testdata/" "camera/app/data/perception/camera/sensor_meta_camera.pt"; FLAGS_obs_sensor_intrinsic_path = "/apollo/modules/perception/testdata/" @@ -101,7 +101,7 @@ TEST(TrafficLightCameraPerceptionTest, bad_proto) { TEST(TrafficLightCameraPerceptionTest, bad_detector) { unsetenv("MODULE_PATH"); - unsetenv("CYBERTRON_PATH"); + unsetenv("CYBER_PATH"); fLS::FLAGS_obs_sensor_meta_path = "/apollo/modules/perception/testdata/" "camera/app/data/perception/camera/sensor_meta_camera.pt"; FLAGS_obs_sensor_intrinsic_path = "/apollo/modules/perception/testdata/" @@ -116,7 +116,7 @@ TEST(TrafficLightCameraPerceptionTest, bad_detector) { TEST(TrafficLightCameraPerceptionTest, bad_recognizer) { unsetenv("MODULE_PATH"); - unsetenv("CYBERTRON_PATH"); + unsetenv("CYBER_PATH"); fLS::FLAGS_obs_sensor_meta_path = "/apollo/modules/perception/testdata/" "camera/app/data/perception/camera/sensor_meta_camera.pt"; FLAGS_obs_sensor_intrinsic_path = "/apollo/modules/perception/testdata/" @@ -131,7 +131,7 @@ TEST(TrafficLightCameraPerceptionTest, bad_recognizer) { TEST(TrafficLightCameraPerceptionTest, bad_tracker) { unsetenv("MODULE_PATH"); - unsetenv("CYBERTRON_PATH"); + unsetenv("CYBER_PATH"); fLS::FLAGS_obs_sensor_meta_path = "/apollo/modules/perception/testdata/" "camera/app/data/perception/camera/sensor_meta_camera.pt"; FLAGS_obs_sensor_intrinsic_path = "/apollo/modules/perception/testdata/" diff --git a/modules/perception/camera/test/camera_common_data_provider_test.cc b/modules/perception/camera/test/camera_common_data_provider_test.cc index 419cd56ac0d..22096353b19 100644 --- a/modules/perception/camera/test/camera_common_data_provider_test.cc +++ b/modules/perception/camera/test/camera_common_data_provider_test.cc @@ -31,7 +31,7 @@ namespace camera { TEST(DataProvider, test_image_options) { unsetenv("MODULE_PATH"); - unsetenv("CYBERTRON_PATH"); + unsetenv("CYBER_PATH"); DataProvider::ImageOptions image_options; EXPECT_EQ(image_options.ToString(), " 0 0"); @@ -42,7 +42,7 @@ TEST(DataProvider, test_image_options) { TEST(DataProvider, test_nodistortion) { unsetenv("MODULE_PATH"); - unsetenv("CYBERTRON_PATH"); + unsetenv("CYBER_PATH"); cv::Mat img = cv::imread("/apollo/modules/perception/testdata/" "camera/common/img/test.jpg"); @@ -123,7 +123,7 @@ TEST(DataProvider, test_nodistortion) { TEST(DataProvider, test_fill_image_data) { unsetenv("MODULE_PATH"); - unsetenv("CYBERTRON_PATH"); + unsetenv("CYBER_PATH"); FLAGS_obs_sensor_meta_path = "/apollo/modules/perception/testdata/" "camera/common/conf/sensor_meta.config"; FLAGS_obs_sensor_intrinsic_path = "/apollo/modules/perception/testdata/" @@ -174,7 +174,7 @@ TEST(DataProvider, test_fill_image_data) { TEST(DataProvider, test_convert_color) { unsetenv("MODULE_PATH"); - unsetenv("CYBERTRON_PATH"); + unsetenv("CYBER_PATH"); FLAGS_obs_sensor_meta_path = "/apollo/modules/perception/testdata/" "camera/common/conf/sensor_meta.config"; FLAGS_obs_sensor_intrinsic_path = "/apollo/modules/perception/testdata/" @@ -281,7 +281,7 @@ TEST(DataProvider, test_convert_color) { TEST(DataProvider, test_undistortion) { unsetenv("MODULE_PATH"); - unsetenv("CYBERTRON_PATH"); + unsetenv("CYBER_PATH"); FLAGS_obs_sensor_meta_path = "/apollo/modules/perception/testdata/" "camera/common/conf/sensor_meta.config"; FLAGS_obs_sensor_intrinsic_path = "/apollo/modules/perception/testdata/" diff --git a/modules/perception/camera/test/camera_common_io_util.h b/modules/perception/camera/test/camera_common_io_util.h index afd8db67644..fd61bd9cd77 100644 --- a/modules/perception/camera/test/camera_common_io_util.h +++ b/modules/perception/camera/test/camera_common_io_util.h @@ -20,7 +20,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace perception { diff --git a/modules/perception/camera/test/camera_common_undistortion_handler_test.cc b/modules/perception/camera/test/camera_common_undistortion_handler_test.cc index 0309c088e9c..6d4ffe68db6 100644 --- a/modules/perception/camera/test/camera_common_undistortion_handler_test.cc +++ b/modules/perception/camera/test/camera_common_undistortion_handler_test.cc @@ -40,7 +40,7 @@ namespace camera { TEST(UndistortionHandlerTest, test_init) { unsetenv("MODULE_PATH"); - unsetenv("CYBERTRON_PATH"); + unsetenv("CYBER_PATH"); { FLAGS_obs_sensor_meta_path = "/apollo/modules/perception/testdata/" "camera/common/conf/sensor_meta.config"; @@ -74,7 +74,7 @@ TEST(UndistortionHandlerTest, test_init) { TEST(UndistortionHandlerTest, test_undistortion) { unsetenv("MODULE_PATH"); - unsetenv("CYBERTRON_PATH"); + unsetenv("CYBER_PATH"); { FLAGS_obs_sensor_meta_path = "/apollo/modules/perception/testdata/" "camera/common/conf/sensor_meta.config"; @@ -114,7 +114,7 @@ TEST(UndistortionHandlerTest, test_undistortion) { TEST(UndistortionHandlerTest, test_verify) { unsetenv("MODULE_PATH"); - unsetenv("CYBERTRON_PATH"); + unsetenv("CYBER_PATH"); { // test RGB undistortion cv::Mat rgb_image = cv::imread("/apollo/modules/perception/testdata/" diff --git a/modules/perception/camera/test/camera_common_util_test.cc b/modules/perception/camera/test/camera_common_util_test.cc index 11a08cc7eb2..594cdabc86b 100644 --- a/modules/perception/camera/test/camera_common_util_test.cc +++ b/modules/perception/camera/test/camera_common_util_test.cc @@ -326,30 +326,30 @@ TEST(UtilTest, test_resize_cpu) { } } -TEST(UtilTest, GetCybertronWorkRootTest) { +TEST(UtilTest, GetCyberWorkRootTest) { unsetenv("MODULE_PATH"); - unsetenv("CYBERTRON_PATH"); + unsetenv("CYBER_PATH"); std::string work_root = ""; - GetCybertronWorkRoot(&work_root); + GetCyberWorkRoot(&work_root); EXPECT_EQ(work_root, ""); - char cybertron_path[] = "CYBERTRON_PATH=/home/caros/cybertron"; - putenv(cybertron_path); - GetCybertronWorkRoot(&work_root); - EXPECT_EQ(work_root, "/home/caros/cybertron"); + char cyber_path[] = "CYBER_PATH=/home/caros/cyber"; + putenv(cyber_path); + GetCyberWorkRoot(&work_root); + EXPECT_EQ(work_root, "/home/caros/cyber"); char module_path[] = "MODULE_PATH=/home/test/perception-camera"; putenv(module_path); - GetCybertronWorkRoot(&work_root); + GetCyberWorkRoot(&work_root); EXPECT_EQ(work_root, "/home/test/perception-camera"); unsetenv("MODULE_PATH"); - GetCybertronWorkRoot(&work_root); - EXPECT_EQ(work_root, "/home/caros/cybertron"); + GetCyberWorkRoot(&work_root); + EXPECT_EQ(work_root, "/home/caros/cyber"); - unsetenv("CYBERTRON_PATH"); - GetCybertronWorkRoot(&work_root); + unsetenv("CYBER_PATH"); + GetCyberWorkRoot(&work_root); EXPECT_EQ(work_root, ""); } diff --git a/modules/perception/camera/test/camera_lib_calibration_service_online_calibration_service_test.cc b/modules/perception/camera/test/camera_lib_calibration_service_online_calibration_service_test.cc index f89ce4e9c55..29bd649f0af 100644 --- a/modules/perception/camera/test/camera_lib_calibration_service_online_calibration_service_test.cc +++ b/modules/perception/camera/test/camera_lib_calibration_service_online_calibration_service_test.cc @@ -16,7 +16,7 @@ #include #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/base/distortion_model.h" #include "modules/perception/camera/lib/calibration_service/online_calibration_service/online_calibration_service.h" // NOLINT #include "modules/perception/common/io/io_util.h" diff --git a/modules/perception/camera/test/camera_lib_calibrator_laneline_laneline_calibrator_test.cc b/modules/perception/camera/test/camera_lib_calibrator_laneline_laneline_calibrator_test.cc index 6c3825828c2..081839c05f9 100644 --- a/modules/perception/camera/test/camera_lib_calibrator_laneline_laneline_calibrator_test.cc +++ b/modules/perception/camera/test/camera_lib_calibrator_laneline_laneline_calibrator_test.cc @@ -20,7 +20,7 @@ #include #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/camera/test/camera_lib_calibrator_laneline_app_util.h" #include "modules/perception/camera/test/camera_lib_calibrator_laneline_lane_calibrator_util.h" // NOLINT diff --git a/modules/perception/camera/test/camera_lib_lane_common_functions_test.cc b/modules/perception/camera/test/camera_lib_lane_common_functions_test.cc index 9ad1f921b04..fabf1c772a6 100644 --- a/modules/perception/camera/test/camera_lib_lane_common_functions_test.cc +++ b/modules/perception/camera/test/camera_lib_lane_common_functions_test.cc @@ -18,7 +18,7 @@ #include #include #include "modules/perception/camera/lib/lane/common/common_functions.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/base/distortion_model.h" #include "modules/perception/common/io/io_util.h" #include "modules/perception/lib/io/file_util.h" diff --git a/modules/perception/camera/test/camera_lib_lane_detector_denseline_lane_detector_test.cc b/modules/perception/camera/test/camera_lib_lane_detector_denseline_lane_detector_test.cc index f3db6b41fc3..4034c4691be 100644 --- a/modules/perception/camera/test/camera_lib_lane_detector_denseline_lane_detector_test.cc +++ b/modules/perception/camera/test/camera_lib_lane_detector_denseline_lane_detector_test.cc @@ -19,7 +19,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/camera/lib/lane/detector/denseline/denseline_lane_detector.h" #include "modules/perception/base/distortion_model.h" #include "modules/perception/common/io/io_util.h" diff --git a/modules/perception/camera/test/camera_lib_lane_postprocessor_denseline_lane_postprocessor_test.cc b/modules/perception/camera/test/camera_lib_lane_postprocessor_denseline_lane_postprocessor_test.cc index 973ef0b37a3..61c35ae8505 100644 --- a/modules/perception/camera/test/camera_lib_lane_postprocessor_denseline_lane_postprocessor_test.cc +++ b/modules/perception/camera/test/camera_lib_lane_postprocessor_denseline_lane_postprocessor_test.cc @@ -21,7 +21,7 @@ #include "modules/perception/camera/common/camera_frame.h" #include "modules/perception/camera/lib/lane/postprocessor/denseline/denseline_lane_postprocessor.h" #include "modules/perception/camera/lib/calibration_service/online_calibration_service/online_calibration_service.h" // NOLINT -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/base/distortion_model.h" #include "modules/perception/common/io/io_util.h" #include "modules/perception/lib/io/file_util.h" @@ -32,7 +32,7 @@ namespace camera { TEST(DenselineLanePostprocessor, camera_lane_postprocessor_point_test) { unsetenv("MODULE_PATH"); - unsetenv("CYBERTRON_PATH"); + unsetenv("CYBER_PATH"); // initialize lane detector LaneDetectorInitOptions init_options; LaneDetectorOptions detetor_options; @@ -145,7 +145,7 @@ TEST(DenselineLanePostprocessor, camera_lane_postprocessor_point_test) { TEST(DenselineLanePostprocessor, lane_postprocessor_init_test) { unsetenv("MODULE_PATH"); - unsetenv("CYBERTRON_PATH"); + unsetenv("CYBER_PATH"); std::shared_ptr lane_postprocessor; lane_postprocessor.reset(new DenselineLanePostprocessor); LanePostprocessorInitOptions postprocessor_init_options; diff --git a/modules/perception/camera/test/camera_lib_obstacle_postprocessor_location_refiner_test.cc b/modules/perception/camera/test/camera_lib_obstacle_postprocessor_location_refiner_test.cc index eda19da21d9..7e42422e5e5 100644 --- a/modules/perception/camera/test/camera_lib_obstacle_postprocessor_location_refiner_test.cc +++ b/modules/perception/camera/test/camera_lib_obstacle_postprocessor_location_refiner_test.cc @@ -20,7 +20,7 @@ #include "modules/perception/camera/lib/obstacle/postprocessor/location_refiner/location_refiner_obstacle_postprocessor.h" // NOLINT #include "modules/perception/camera/lib/calibration_service/online_calibration_service/online_calibration_service.h" // NOLINT #include "modules/perception/common/io/io_util.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace perception { diff --git a/modules/perception/camera/test/camera_lib_obstacle_tracker_common_test.cc b/modules/perception/camera/test/camera_lib_obstacle_tracker_common_test.cc index ee1c8219176..f1b7938e242 100644 --- a/modules/perception/camera/test/camera_lib_obstacle_tracker_common_test.cc +++ b/modules/perception/camera/test/camera_lib_obstacle_tracker_common_test.cc @@ -21,7 +21,7 @@ #include "modules/perception/camera/lib/obstacle/tracker/common/kalman_filter.h" #include "modules/perception/inference/utils/cuda_util.h" #include "modules/perception/camera/lib/obstacle/tracker/common/similar.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "gtest/gtest.h" namespace apollo { diff --git a/modules/perception/camera/test/camera_lib_obstacle_tracker_omt_omt_obstacle_tracker_test.cc b/modules/perception/camera/test/camera_lib_obstacle_tracker_omt_omt_obstacle_tracker_test.cc index cf7d85d5525..8112f079816 100644 --- a/modules/perception/camera/test/camera_lib_obstacle_tracker_omt_omt_obstacle_tracker_test.cc +++ b/modules/perception/camera/test/camera_lib_obstacle_tracker_omt_omt_obstacle_tracker_test.cc @@ -24,7 +24,7 @@ #include "modules/perception/base/object.h" #include "modules/perception/base/object_types.h" #include "modules/perception/base/distortion_model.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/camera/common/camera_frame.h" #include "modules/perception/camera/lib/interface/base_obstacle_tracker.h" #include "modules/perception/camera/lib/interface/base_obstacle_detector.h" diff --git a/modules/perception/camera/test/camera_lib_traffic_light_detector_crop_test.cc b/modules/perception/camera/test/camera_lib_traffic_light_detector_crop_test.cc index 115a55ae62e..8196645ce72 100644 --- a/modules/perception/camera/test/camera_lib_traffic_light_detector_crop_test.cc +++ b/modules/perception/camera/test/camera_lib_traffic_light_detector_crop_test.cc @@ -16,7 +16,7 @@ #include "modules/perception/camera/lib/traffic_light/detector/detection/cropbox.h" #include "gtest/gtest.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace perception { diff --git a/modules/perception/camera/test/camera_lib_traffic_light_detector_detection_test.cc b/modules/perception/camera/test/camera_lib_traffic_light_detector_detection_test.cc index 7f7c536caa5..856e70f8655 100644 --- a/modules/perception/camera/test/camera_lib_traffic_light_detector_detection_test.cc +++ b/modules/perception/camera/test/camera_lib_traffic_light_detector_detection_test.cc @@ -23,7 +23,7 @@ namespace camera { TEST(DetectionTest, init_test) { unsetenv("MODULE_PATH"); - unsetenv("CYBERTRON_PATH"); + unsetenv("CYBER_PATH"); { std::shared_ptr detector(new TrafficLightDetection); TrafficLightDetectorInitOptions init_options; @@ -56,7 +56,7 @@ TEST(DetectionTest, init_test) { TEST(DetectionTest, all) { unsetenv("MODULE_PATH"); - unsetenv("CYBERTRON_PATH"); + unsetenv("CYBER_PATH"); std::shared_ptr detector(new TrafficLightDetection); TrafficLightDetectorInitOptions init_options; TrafficLightDetectorOptions detetor_options; @@ -139,7 +139,7 @@ TEST(DetectionTest, all) { TEST(DetectionTest, no_light) { unsetenv("MODULE_PATH"); - unsetenv("CYBERTRON_PATH"); + unsetenv("CYBER_PATH"); std::shared_ptr detector(new TrafficLightDetection); AINFO << detector->Name(); TrafficLightDetectorInitOptions init_options; @@ -190,7 +190,7 @@ TEST(DetectionTest, no_light) { TEST(DetectionTest, out_of_img_light) { unsetenv("MODULE_PATH"); - unsetenv("CYBERTRON_PATH"); + unsetenv("CYBER_PATH"); std::shared_ptr detector(new TrafficLightDetection); TrafficLightDetectorInitOptions init_options; TrafficLightDetectorOptions detetor_options; @@ -264,7 +264,7 @@ TEST(DetectionTest, out_of_img_light) { TEST(DetectionTest, nms_test) { unsetenv("MODULE_PATH"); - unsetenv("CYBERTRON_PATH"); + unsetenv("CYBER_PATH"); std::shared_ptr detector(new TrafficLightDetection); TrafficLightDetectorInitOptions init_options; TrafficLightDetectorOptions detetor_options; diff --git a/modules/perception/camera/test/camera_lib_traffic_light_detector_select_test.cc b/modules/perception/camera/test/camera_lib_traffic_light_detector_select_test.cc index a878cfd985a..2ab9f0190c6 100644 --- a/modules/perception/camera/test/camera_lib_traffic_light_detector_select_test.cc +++ b/modules/perception/camera/test/camera_lib_traffic_light_detector_select_test.cc @@ -16,7 +16,7 @@ #include "modules/perception/camera/lib/traffic_light/detector/detection/select.h" #include "gtest/gtest.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace perception { diff --git a/modules/perception/camera/test/camera_lib_traffic_light_preprocessor_test.cc b/modules/perception/camera/test/camera_lib_traffic_light_preprocessor_test.cc index ed864495ab2..e1157656cb5 100644 --- a/modules/perception/camera/test/camera_lib_traffic_light_preprocessor_test.cc +++ b/modules/perception/camera/test/camera_lib_traffic_light_preprocessor_test.cc @@ -18,7 +18,7 @@ #include "gtest/gtest.h" #include "modules/perception/camera/lib/traffic_light/preprocessor/tl_preprocessor.h" #include "modules/perception/base/point.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/lib/io/file_util.h" #include "modules/perception/common/sensor_manager/sensor_manager.h" @@ -34,7 +34,7 @@ class TLPreprocessorTest : public ::testing::Test { protected: virtual void SetUp() { unsetenv("MODULE_PATH"); - unsetenv("CYBERTRON_PATH"); + unsetenv("CYBER_PATH"); FLAGS_obs_sensor_meta_path = "/apollo/modules/perception/testdata/" "camera/lib/traffic_light/preprocessor/conf/sensor_meta.config"; FLAGS_obs_sensor_intrinsic_path = "/apollo/modules/perception/testdata/" @@ -161,7 +161,7 @@ class TLPreprocessorTest : public ::testing::Test { TEST_F(TLPreprocessorTest, test_set_and_get_camera_is_working_flag) { unsetenv("MODULE_PATH"); - unsetenv("CYBERTRON_PATH"); + unsetenv("CYBER_PATH"); TrafficLightPreprocessorInitOptions init_options; init_options.conf_file = "preprocess.pt"; init_options.root_dir = "/apollo/modules/perception/testdata/" @@ -201,7 +201,7 @@ TEST_F(TLPreprocessorTest, test_set_and_get_camera_is_working_flag) { TEST_F(TLPreprocessorTest, test_project_lights) { unsetenv("MODULE_PATH"); - unsetenv("CYBERTRON_PATH"); + unsetenv("CYBER_PATH"); TrafficLightPreprocessorInitOptions init_options; init_options.conf_file = "preprocess.pt"; init_options.root_dir = "/apollo/modules/perception/testdata/" @@ -344,7 +344,7 @@ TEST_F(TLPreprocessorTest, test_project_lights) { TEST_F(TLPreprocessorTest, test_select_camera) { unsetenv("MODULE_PATH"); - unsetenv("CYBERTRON_PATH"); + unsetenv("CYBER_PATH"); TrafficLightPreprocessorInitOptions init_options; init_options.conf_file = "preprocess.pt"; init_options.root_dir = "/apollo/modules/perception/testdata/" @@ -467,7 +467,7 @@ TEST_F(TLPreprocessorTest, test_select_camera) { TEST_F(TLPreprocessorTest, test_get_max_min_focal_len_camera_id) { unsetenv("MODULE_PATH"); - unsetenv("CYBERTRON_PATH"); + unsetenv("CYBER_PATH"); TrafficLightPreprocessorInitOptions init_options; init_options.conf_file = "preprocess.pt"; init_options.root_dir = "/apollo/modules/perception/testdata/" @@ -523,7 +523,7 @@ TEST_F(TLPreprocessorTest, test_get_max_min_focal_len_camera_id) { TEST_F(TLPreprocessorTest, invalid_pose_id) { unsetenv("MODULE_PATH"); - unsetenv("CYBERTRON_PATH"); + unsetenv("CYBER_PATH"); CarPose pose; Eigen::Matrix4d c2w_pose; std::vector lights(1); @@ -540,7 +540,7 @@ TEST_F(TLPreprocessorTest, invalid_pose_id) { TEST_F(TLPreprocessorTest, invalid_camera_name) { unsetenv("MODULE_PATH"); - unsetenv("CYBERTRON_PATH"); + unsetenv("CYBER_PATH"); CarPose pose; Eigen::Matrix4d c2w_pose; std::vector lights(1); @@ -568,7 +568,7 @@ TEST_F(TLPreprocessorTest, invalid_camera_name) { TEST_F(TLPreprocessorTest, on_board) { unsetenv("MODULE_PATH"); - unsetenv("CYBERTRON_PATH"); + unsetenv("CYBER_PATH"); TrafficLightPreprocessorInitOptions init_options; init_options.conf_file = "preprocess.pt"; init_options.root_dir = "/apollo/modules/perception/testdata/" @@ -655,7 +655,7 @@ TEST_F(TLPreprocessorTest, on_board) { TEST_F(TLPreprocessorTest, UpdateLightsProjectionTest) { unsetenv("MODULE_PATH"); - unsetenv("CYBERTRON_PATH"); + unsetenv("CYBER_PATH"); TrafficLightPreprocessorInitOptions init_options; init_options.conf_file = "preprocess.pt"; init_options.root_dir = "/apollo/modules/perception/testdata/" diff --git a/modules/perception/camera/test/camera_lib_traffic_light_tracker_test.cc b/modules/perception/camera/test/camera_lib_traffic_light_tracker_test.cc index 8da620d528f..0978df146c2 100644 --- a/modules/perception/camera/test/camera_lib_traffic_light_tracker_test.cc +++ b/modules/perception/camera/test/camera_lib_traffic_light_tracker_test.cc @@ -19,7 +19,7 @@ #include "gtest/gtest.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/base/distortion_model.h" #include "modules/perception/common/io/io_util.h" #include "modules/perception/camera/lib/traffic_light/tracker/semantic_decision.h" diff --git a/modules/perception/camera/tools/lane_detection/BUILD b/modules/perception/camera/tools/lane_detection/BUILD index c9ecf8726f5..e47eab9f915 100644 --- a/modules/perception/camera/tools/lane_detection/BUILD +++ b/modules/perception/camera/tools/lane_detection/BUILD @@ -11,7 +11,7 @@ cc_library( "lane_common.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/perception/base:base", "//modules/perception/camera/lib/lane/common:common_functions", ] @@ -30,7 +30,7 @@ cc_binary( deps = [ ":lane_common", "//external:gflags", - "//cybertron", + "//cyber", "//modules/common/util:file_util", "//modules/perception/base:base", "//modules/perception/camera/common:common", diff --git a/modules/perception/camera/tools/lane_detection/lane_common.cc b/modules/perception/camera/tools/lane_detection/lane_common.cc index cbcd566d339..854e9b6f4fe 100644 --- a/modules/perception/camera/tools/lane_detection/lane_common.cc +++ b/modules/perception/camera/tools/lane_detection/lane_common.cc @@ -17,7 +17,7 @@ #include #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" DEFINE_string(list, "test.list", "test file title"); DEFINE_string(file_title, "", "test file title"); diff --git a/modules/perception/camera/tools/lane_detection/lane_denseline_eval.cc b/modules/perception/camera/tools/lane_detection/lane_denseline_eval.cc index 01f5ad7438b..9497ec4ffd9 100644 --- a/modules/perception/camera/tools/lane_detection/lane_denseline_eval.cc +++ b/modules/perception/camera/tools/lane_detection/lane_denseline_eval.cc @@ -19,7 +19,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/base/distortion_model.h" #include "modules/perception/camera/common/camera_frame.h" #include "modules/perception/camera/lib/calibration_service/online_calibration_service/online_calibration_service.h" diff --git a/modules/perception/camera/tools/offline/BUILD b/modules/perception/camera/tools/offline/BUILD index dd3bb127177..4fcf06bad81 100644 --- a/modules/perception/camera/tools/offline/BUILD +++ b/modules/perception/camera/tools/offline/BUILD @@ -33,7 +33,7 @@ cc_library( deps = [ "@eigen", "@yaml_cpp//:yaml", - "//cybertron", + "//cyber", "//modules/perception/base:base", "//modules/perception/camera/common:common", ] diff --git a/modules/perception/camera/tools/offline/offline_obstacle_pipeline.cc b/modules/perception/camera/tools/offline/offline_obstacle_pipeline.cc index ce2706283c6..1b986f3926f 100644 --- a/modules/perception/camera/tools/offline/offline_obstacle_pipeline.cc +++ b/modules/perception/camera/tools/offline/offline_obstacle_pipeline.cc @@ -37,7 +37,7 @@ DEFINE_string(config_file, "obstacle.pt", "config_file"); DEFINE_string(narrow_name, "onsemi_narrow", " camera for projecting"); DEFINE_string(base_camera_name, "onsemi_obstacle", "camera to be peojected"); DEFINE_string(sensor_name, "onsemi_obstacle,onsemi_narrow", "camera to use"); -DEFINE_string(params_dir, "/home/caros/cybertron/params", "params dir"); +DEFINE_string(params_dir, "/home/caros/cyber/params", "params dir"); DEFINE_string(visualize_dir, "/tmp/0000", "visualize dir"); DEFINE_double(camera_fps, 15, "camera_fps"); DEFINE_bool(do_undistortion, false, "do_undistortion"); diff --git a/modules/perception/camera/tools/offline/transform_server.cc b/modules/perception/camera/tools/offline/transform_server.cc index 11b4a564323..c690e3d0e26 100644 --- a/modules/perception/camera/tools/offline/transform_server.cc +++ b/modules/perception/camera/tools/offline/transform_server.cc @@ -16,7 +16,7 @@ #include #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/camera/tools/offline/transform_server.h" #include "modules/perception/camera/common/util.h" diff --git a/modules/perception/camera/tools/offline/visualizer.cc b/modules/perception/camera/tools/offline/visualizer.cc index 07b52a5e5e2..40ec68183e8 100644 --- a/modules/perception/camera/tools/offline/visualizer.cc +++ b/modules/perception/camera/tools/offline/visualizer.cc @@ -16,7 +16,7 @@ #include "modules/perception/camera/tools/offline/visualizer.h" #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace perception { namespace camera { diff --git a/modules/perception/common/graph/BUILD b/modules/perception/common/graph/BUILD index 18a6a0eadc4..3f454a19ce1 100644 --- a/modules/perception/common/graph/BUILD +++ b/modules/perception/common/graph/BUILD @@ -46,7 +46,7 @@ cc_library( "graph_segmentor.h", ], deps = [ - "//cybertron", + "//cyber", ":disjoint_set", ], ) @@ -115,7 +115,7 @@ cc_library( "connected_component_analysis.h", ], deps = [ - "//cybertron", + "//cyber", ], ) @@ -162,7 +162,7 @@ cc_library( "gated_hungarian_bigraph_matcher.h", ], deps = [ - "//cybertron", + "//cyber", ":connected_component_analysis", ":hungarian_optimizer", ":secure_matrix", diff --git a/modules/perception/common/graph/connected_component_analysis.h b/modules/perception/common/graph/connected_component_analysis.h index 3bcb1be1e17..2725254ec70 100644 --- a/modules/perception/common/graph/connected_component_analysis.h +++ b/modules/perception/common/graph/connected_component_analysis.h @@ -19,7 +19,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace perception { diff --git a/modules/perception/common/graph/gated_hungarian_bigraph_matcher.h b/modules/perception/common/graph/gated_hungarian_bigraph_matcher.h index 0c9b4775c8c..35d33c7b038 100644 --- a/modules/perception/common/graph/gated_hungarian_bigraph_matcher.h +++ b/modules/perception/common/graph/gated_hungarian_bigraph_matcher.h @@ -23,7 +23,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/common/graph/connected_component_analysis.h" #include "modules/perception/common/graph/hungarian_optimizer.h" diff --git a/modules/perception/common/graph/graph_segmentor.cc b/modules/perception/common/graph/graph_segmentor.cc index bc658e40c08..a4c1a4cd6ca 100644 --- a/modules/perception/common/graph/graph_segmentor.cc +++ b/modules/perception/common/graph/graph_segmentor.cc @@ -19,7 +19,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace perception { diff --git a/modules/perception/common/i_lib/algorithm/BUILD b/modules/perception/common/i_lib/algorithm/BUILD index 6b87ad12221..aa569c5febd 100644 --- a/modules/perception/common/i_lib/algorithm/BUILD +++ b/modules/perception/common/i_lib/algorithm/BUILD @@ -8,7 +8,7 @@ cc_library( "i_sort.h", ], deps = [ - "//cybertron", + "//cyber", ], ) diff --git a/modules/perception/common/io/BUILD b/modules/perception/common/io/BUILD index dd4217fac18..e93c52446fe 100644 --- a/modules/perception/common/io/BUILD +++ b/modules/perception/common/io/BUILD @@ -11,7 +11,7 @@ cc_library( "io_util.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/perception/base:camera", "//modules/perception/base:distortion_model", "//modules/perception/base:omnidirectional_model", diff --git a/modules/perception/common/io/io_util.cc b/modules/perception/common/io/io_util.cc index 13f6c71cc70..2199235919e 100644 --- a/modules/perception/common/io/io_util.cc +++ b/modules/perception/common/io/io_util.cc @@ -26,7 +26,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/base/camera.h" #include "modules/perception/lib/io/file_util.h" #include "yaml-cpp/yaml.h" diff --git a/modules/perception/common/point_cloud_processing/BUILD b/modules/perception/common/point_cloud_processing/BUILD index 7b92dcf2198..2371f590d48 100644 --- a/modules/perception/common/point_cloud_processing/BUILD +++ b/modules/perception/common/point_cloud_processing/BUILD @@ -9,7 +9,7 @@ cc_library( "downsampling.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/perception/base:point_cloud", "//modules/perception/common/geometry:basic", ], diff --git a/modules/perception/common/point_cloud_processing/downsampling.h b/modules/perception/common/point_cloud_processing/downsampling.h index d86dc6b45b2..95f21d1e4a2 100644 --- a/modules/perception/common/point_cloud_processing/downsampling.h +++ b/modules/perception/common/point_cloud_processing/downsampling.h @@ -20,7 +20,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/base/point_cloud.h" #include "modules/perception/common/geometry/basic.h" diff --git a/modules/perception/common/production/conf/perception/common/perception_common.flag b/modules/perception/common/production/conf/perception/common/perception_common.flag index c5c66fc9512..2da789aa833 100644 --- a/modules/perception/common/production/conf/perception/common/perception_common.flag +++ b/modules/perception/common/production/conf/perception/common/perception_common.flag @@ -9,4 +9,4 @@ # The intrinsics/extrinsics dir # type: string # default: ---obs_sensor_intrinsic_path=/home/caros/cybertron/params +--obs_sensor_intrinsic_path=/home/caros/cyber/params diff --git a/modules/perception/common/sensor_manager/BUILD b/modules/perception/common/sensor_manager/BUILD index 2be8672dda0..4dc503cb885 100644 --- a/modules/perception/common/sensor_manager/BUILD +++ b/modules/perception/common/sensor_manager/BUILD @@ -11,7 +11,7 @@ cc_library( "sensor_manager.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/perception/base:base_type", "//modules/perception/base:camera", "//modules/perception/base:omnidirectional_model", diff --git a/modules/perception/common/sensor_manager/sensor_manager.cc b/modules/perception/common/sensor_manager/sensor_manager.cc index 2d3cfa92e91..c95fec57fd4 100644 --- a/modules/perception/common/sensor_manager/sensor_manager.cc +++ b/modules/perception/common/sensor_manager/sensor_manager.cc @@ -19,7 +19,7 @@ #include #include "google/protobuf/text_format.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/lib/config_manager/config_manager.h" #include "modules/perception/lib/io/file_util.h" #include "modules/perception/common/io/io_util.h" diff --git a/modules/perception/fusion/app/BUILD b/modules/perception/fusion/app/BUILD index 44fd4f79cff..9868333e548 100644 --- a/modules/perception/fusion/app/BUILD +++ b/modules/perception/fusion/app/BUILD @@ -12,7 +12,7 @@ cc_library( ], deps = [ "@eigen", - "//cybertron", + "//cyber", "//modules/perception/base", "//modules/perception/fusion/base", "//modules/perception/fusion/lib/interface", diff --git a/modules/perception/fusion/base/BUILD b/modules/perception/fusion/base/BUILD index 2eeb5ed3fc9..239f3c98508 100644 --- a/modules/perception/fusion/base/BUILD +++ b/modules/perception/fusion/base/BUILD @@ -71,7 +71,7 @@ cc_library( ], deps = [ ":base_forward_declaration", - "//cybertron", + "//cyber", "//modules/perception/base", "//modules/perception/base:base_type", "//modules/perception/base:frame", diff --git a/modules/perception/fusion/base/base_init_options.cc b/modules/perception/fusion/base/base_init_options.cc index c69f8bc1fc0..b5aea3345c9 100644 --- a/modules/perception/fusion/base/base_init_options.cc +++ b/modules/perception/fusion/base/base_init_options.cc @@ -15,7 +15,7 @@ *****************************************************************************/ #include "modules/perception/fusion/base/base_init_options.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/lib/config_manager/config_manager.h" diff --git a/modules/perception/fusion/base/fusion_log.h b/modules/perception/fusion/base/fusion_log.h index 0f419364662..15dbb5dc0ff 100644 --- a/modules/perception/fusion/base/fusion_log.h +++ b/modules/perception/fusion/base/fusion_log.h @@ -15,7 +15,7 @@ *****************************************************************************/ #pragma once -#include "cybertron/common/log.h" +#include "cyber/common/log.h" // 500-599 reserve for fusion module error #define FUSION_GET_POSE_ERROR 500 // get pose error #define FUSION_GET_HDMAP_ERROR 501 // get hdmap error diff --git a/modules/perception/fusion/base/sensor.cc b/modules/perception/fusion/base/sensor.cc index aad5607571c..26462873bdf 100644 --- a/modules/perception/fusion/base/sensor.cc +++ b/modules/perception/fusion/base/sensor.cc @@ -16,7 +16,7 @@ #include "modules/perception/fusion/base/sensor.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace perception { diff --git a/modules/perception/fusion/base/sensor_data_manager.cc b/modules/perception/fusion/base/sensor_data_manager.cc index 099ae300d8f..89c72d78c6c 100644 --- a/modules/perception/fusion/base/sensor_data_manager.cc +++ b/modules/perception/fusion/base/sensor_data_manager.cc @@ -17,7 +17,7 @@ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace perception { diff --git a/modules/perception/fusion/base/track_pool_types.cc b/modules/perception/fusion/base/track_pool_types.cc index d71ebd59f62..0729db44bf4 100644 --- a/modules/perception/fusion/base/track_pool_types.cc +++ b/modules/perception/fusion/base/track_pool_types.cc @@ -15,7 +15,7 @@ *****************************************************************************/ #include "modules/perception/fusion/base/track_pool_types.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace perception { diff --git a/modules/perception/fusion/common/BUILD b/modules/perception/fusion/common/BUILD index ec018b9c6e5..56c68d65f68 100644 --- a/modules/perception/fusion/common/BUILD +++ b/modules/perception/fusion/common/BUILD @@ -49,7 +49,7 @@ cc_library( "dst_evidence.h", ], deps = [ - "//cybertron", + "//cyber", ], ) @@ -102,7 +102,7 @@ cc_library( ], deps = [ ":base_filter", - "//cybertron", + "//cyber", ], ) diff --git a/modules/perception/fusion/common/camera_util_test.cc b/modules/perception/fusion/common/camera_util_test.cc index 467db601045..0da310ab1ae 100644 --- a/modules/perception/fusion/common/camera_util_test.cc +++ b/modules/perception/fusion/common/camera_util_test.cc @@ -16,7 +16,7 @@ #include #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/fusion/base/sensor_data_manager.h" #include "modules/perception/fusion/common/camera_util.h" diff --git a/modules/perception/fusion/common/dst_evidence.cc b/modules/perception/fusion/common/dst_evidence.cc index 59f66389e91..ebeb89a4f1c 100644 --- a/modules/perception/fusion/common/dst_evidence.cc +++ b/modules/perception/fusion/common/dst_evidence.cc @@ -20,7 +20,7 @@ #include "boost/format.hpp" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace perception { diff --git a/modules/perception/fusion/common/dst_evidence_test.cc b/modules/perception/fusion/common/dst_evidence_test.cc index 6556a713106..e89a369dd41 100644 --- a/modules/perception/fusion/common/dst_evidence_test.cc +++ b/modules/perception/fusion/common/dst_evidence_test.cc @@ -21,7 +21,7 @@ #include "boost/format.hpp" #include "gtest/gtest.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/fusion/common/dst_evidence.h" diff --git a/modules/perception/fusion/common/information_filter_test.cc b/modules/perception/fusion/common/information_filter_test.cc index 01c87cd9c90..60fecc89691 100644 --- a/modules/perception/fusion/common/information_filter_test.cc +++ b/modules/perception/fusion/common/information_filter_test.cc @@ -15,7 +15,7 @@ *****************************************************************************/ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/fusion/common/information_filter.h" namespace apollo { diff --git a/modules/perception/fusion/common/kalman_filter.cc b/modules/perception/fusion/common/kalman_filter.cc index 9c8d4097a27..d78e08e175f 100644 --- a/modules/perception/fusion/common/kalman_filter.cc +++ b/modules/perception/fusion/common/kalman_filter.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ #include "modules/perception/fusion/common/kalman_filter.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace perception { diff --git a/modules/perception/fusion/common/kalman_filter_test.cc b/modules/perception/fusion/common/kalman_filter_test.cc index 265027ddb80..10a57e61d8d 100644 --- a/modules/perception/fusion/common/kalman_filter_test.cc +++ b/modules/perception/fusion/common/kalman_filter_test.cc @@ -17,7 +17,7 @@ #include #include #define private public -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/fusion/common/kalman_filter.h" namespace apollo { diff --git a/modules/perception/fusion/lib/dummy/BUILD b/modules/perception/fusion/lib/dummy/BUILD index 477da1a84f6..4833155adb8 100644 --- a/modules/perception/fusion/lib/dummy/BUILD +++ b/modules/perception/fusion/lib/dummy/BUILD @@ -11,7 +11,7 @@ cc_library( "dummy_algorithms.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/perception/fusion/base", "//modules/perception/fusion/lib/interface", "@eigen", diff --git a/modules/perception/fusion/lib/fusion_system/probabilistic_fusion/BUILD b/modules/perception/fusion/lib/fusion_system/probabilistic_fusion/BUILD index 4e46abedc46..730714d223c 100644 --- a/modules/perception/fusion/lib/fusion_system/probabilistic_fusion/BUILD +++ b/modules/perception/fusion/lib/fusion_system/probabilistic_fusion/BUILD @@ -32,7 +32,7 @@ cc_library( "//modules/perception/proto:pbf_tracker_config_proto", "//modules/perception/proto:perception_config_schema_proto", "//modules/perception/proto:probabilistic_fusion_config_proto", - "//cybertron", + "//cyber", "@eigen", ], ) diff --git a/modules/perception/inference/caffe/caffe_net.cc b/modules/perception/inference/caffe/caffe_net.cc index c8659a9fbaf..0ee67d4edae 100644 --- a/modules/perception/inference/caffe/caffe_net.cc +++ b/modules/perception/inference/caffe/caffe_net.cc @@ -18,7 +18,7 @@ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace perception { diff --git a/modules/perception/inference/tensorrt/BUILD b/modules/perception/inference/tensorrt/BUILD index 01526afb6b4..d75e483a17b 100644 --- a/modules/perception/inference/tensorrt/BUILD +++ b/modules/perception/inference/tensorrt/BUILD @@ -11,7 +11,7 @@ cc_library( "rt_common.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/perception/base:common", "//modules/perception/proto:rt_proto", "@tensorrt", @@ -38,7 +38,7 @@ cc_library( ], deps = [ "//modules/perception/proto:rt_proto", - "//cybertron", + "//cyber", "@tensorrt", ], ) @@ -72,7 +72,7 @@ cc_library( "//modules/perception/proto:rt_proto", "//modules/perception/inference:inference_lib", "//modules/perception/inference/tensorrt/plugins:perception_inference_tensorrt_plugins", - "//cybertron", + "//cyber", "@tensorrt", ], ) @@ -129,7 +129,7 @@ cc_library( linkopts = ["-lopencv_core -lnvinfer_plugin -lopencv_imgproc -lopencv_highgui -lprotobuf -lcaffe"], deps = [ "//modules/perception/proto:rt_proto", - "//cybertron", + "//cyber", "@tensorrt", ], ) diff --git a/modules/perception/inference/tensorrt/batch_stream.cc b/modules/perception/inference/tensorrt/batch_stream.cc index 691c5d7330e..722455f4518 100644 --- a/modules/perception/inference/tensorrt/batch_stream.cc +++ b/modules/perception/inference/tensorrt/batch_stream.cc @@ -20,7 +20,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace perception { diff --git a/modules/perception/inference/tensorrt/batch_stream_test.cc b/modules/perception/inference/tensorrt/batch_stream_test.cc index dc633421386..0cefd0a6831 100644 --- a/modules/perception/inference/tensorrt/batch_stream_test.cc +++ b/modules/perception/inference/tensorrt/batch_stream_test.cc @@ -23,7 +23,7 @@ #include "gtest/gtest.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace perception { diff --git a/modules/perception/inference/tensorrt/entropy_calibrator_test.cc b/modules/perception/inference/tensorrt/entropy_calibrator_test.cc index 662ce055c19..659127cfce4 100644 --- a/modules/perception/inference/tensorrt/entropy_calibrator_test.cc +++ b/modules/perception/inference/tensorrt/entropy_calibrator_test.cc @@ -18,7 +18,7 @@ #include #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "gtest/gtest.h" #define private public diff --git a/modules/perception/inference/tensorrt/rt_common.h b/modules/perception/inference/tensorrt/rt_common.h index 41bc8c240e9..72d23f8cc75 100644 --- a/modules/perception/inference/tensorrt/rt_common.h +++ b/modules/perception/inference/tensorrt/rt_common.h @@ -37,7 +37,7 @@ #include "NvCaffeParser.h" #include "NvInfer.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/base/common.h" #include "modules/perception/proto/rt.pb.h" diff --git a/modules/perception/inference/tensorrt/rt_net.cc b/modules/perception/inference/tensorrt/rt_net.cc index 4e538e34cbd..6caff17971a 100644 --- a/modules/perception/inference/tensorrt/rt_net.cc +++ b/modules/perception/inference/tensorrt/rt_net.cc @@ -24,7 +24,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/inference/tensorrt/plugins/argmax_plugin.h" #include "modules/perception/inference/tensorrt/plugins/slice_plugin.h" #include "modules/perception/inference/tensorrt/plugins/softmax_plugin.h" diff --git a/modules/perception/inference/tensorrt/rt_utils.cc b/modules/perception/inference/tensorrt/rt_utils.cc index faf4586250a..90341241095 100644 --- a/modules/perception/inference/tensorrt/rt_utils.cc +++ b/modules/perception/inference/tensorrt/rt_utils.cc @@ -21,7 +21,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace perception { diff --git a/modules/perception/inference/tools/cal_table_generator.cc b/modules/perception/inference/tools/cal_table_generator.cc index 2872444c4d4..1276f1fcf57 100644 --- a/modules/perception/inference/tools/cal_table_generator.cc +++ b/modules/perception/inference/tools/cal_table_generator.cc @@ -18,7 +18,7 @@ #include "gflags/gflags.h" #include "opencv2/opencv.hpp" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/inference/inference.h" #include "modules/perception/inference/tensorrt/batch_stream.h" #include "modules/perception/inference/tensorrt/entropy_calibrator.h" diff --git a/modules/perception/inference/tools/denseline_sample.cc b/modules/perception/inference/tools/denseline_sample.cc index c9bed8d3d4c..3e3852c9f55 100644 --- a/modules/perception/inference/tools/denseline_sample.cc +++ b/modules/perception/inference/tools/denseline_sample.cc @@ -18,7 +18,7 @@ #include "gflags/gflags.h" #include "opencv2/opencv.hpp" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/inference/inference.h" #include "modules/perception/inference/inference_factory.h" #include "modules/perception/inference/tensorrt/batch_stream.h" diff --git a/modules/perception/inference/tools/lane_sample.cc b/modules/perception/inference/tools/lane_sample.cc index 55aa14a8f8b..0e82ad70154 100644 --- a/modules/perception/inference/tools/lane_sample.cc +++ b/modules/perception/inference/tools/lane_sample.cc @@ -18,7 +18,7 @@ #include "gflags/gflags.h" #include "opencv2/opencv.hpp" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/inference/inference.h" #include "modules/perception/inference/inference_factory.h" #include "modules/perception/inference/tensorrt/batch_stream.h" diff --git a/modules/perception/inference/utils/BUILD b/modules/perception/inference/utils/BUILD index 8ec9b2bcdb3..9d45f5bdd6d 100644 --- a/modules/perception/inference/utils/BUILD +++ b/modules/perception/inference/utils/BUILD @@ -12,7 +12,7 @@ cuda_library( "cuda_util.h", ], deps = [ - "//cybertron", + "//cyber", "@cuda", ], ) @@ -37,7 +37,7 @@ cuda_library( "util.h", ], deps = [ - "//cybertron", + "//cyber", "@cuda", "@eigen", ], @@ -69,7 +69,7 @@ cuda_library( "resize.h", ], deps = [ - "//cybertron", + "//cyber", ":inference_util_lib", ":inference_cuda_util_lib", "//modules/perception/base:blob", @@ -99,7 +99,7 @@ cuda_library( "gemm.h", ], deps = [ - "//cybertron", + "//cyber", ":inference_util_lib", ":inference_cuda_util_lib", "//modules/perception/base:blob", diff --git a/modules/perception/inference/utils/binary_data.cc b/modules/perception/inference/utils/binary_data.cc index eaef8753856..eae54c537fb 100644 --- a/modules/perception/inference/utils/binary_data.cc +++ b/modules/perception/inference/utils/binary_data.cc @@ -17,7 +17,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/inference/utils/binary_data.h" namespace apollo { diff --git a/modules/perception/inference/utils/cuda_util.cu b/modules/perception/inference/utils/cuda_util.cu index 68b239a4ade..05aff01f09d 100644 --- a/modules/perception/inference/utils/cuda_util.cu +++ b/modules/perception/inference/utils/cuda_util.cu @@ -19,7 +19,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace perception { diff --git a/modules/perception/inference/utils/resize.cu b/modules/perception/inference/utils/resize.cu index 581276f0abd..65d934212ab 100644 --- a/modules/perception/inference/utils/resize.cu +++ b/modules/perception/inference/utils/resize.cu @@ -18,7 +18,7 @@ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/inference/utils/util.h" #include "modules/perception/inference/utils/cuda_util.h" diff --git a/modules/perception/inference/utils/util.cc b/modules/perception/inference/utils/util.cc index 7447d6cce74..04064b53dba 100644 --- a/modules/perception/inference/utils/util.cc +++ b/modules/perception/inference/utils/util.cc @@ -16,7 +16,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/inference/utils/util.h" namespace apollo { diff --git a/modules/perception/inference/utils/util.cu b/modules/perception/inference/utils/util.cu index c6472a90978..558b93eaffe 100644 --- a/modules/perception/inference/utils/util.cu +++ b/modules/perception/inference/utils/util.cu @@ -18,7 +18,7 @@ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace perception { diff --git a/modules/perception/lib/config_manager/BUILD b/modules/perception/lib/config_manager/BUILD index 3c41505dc55..a9b1e8c94fb 100644 --- a/modules/perception/lib/config_manager/BUILD +++ b/modules/perception/lib/config_manager/BUILD @@ -11,7 +11,7 @@ cc_library( "config_manager.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/perception/common:perception_gflags", "//modules/perception/lib/io:file_util", "//modules/perception/lib/singleton", diff --git a/modules/perception/lib/config_manager/config_manager.cc b/modules/perception/lib/config_manager/config_manager.cc index e46565a699c..5de0cbcc5fa 100644 --- a/modules/perception/lib/config_manager/config_manager.cc +++ b/modules/perception/lib/config_manager/config_manager.cc @@ -17,7 +17,7 @@ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "google/protobuf/text_format.h" #include "modules/perception/common/perception_gflags.h" @@ -37,7 +37,7 @@ ConfigManager::ConfigManager() { if (work_root_.empty()) { work_root_ = get_env("MODULE_PATH"); if (work_root_.empty()) { - work_root_ = get_env("CYBERTRON_PATH"); + work_root_ = get_env("CYBER_PATH"); } } } diff --git a/modules/perception/lib/config_manager/config_manager_test.cc b/modules/perception/lib/config_manager/config_manager_test.cc index e8a6264f4c0..3502fbee379 100644 --- a/modules/perception/lib/config_manager/config_manager_test.cc +++ b/modules/perception/lib/config_manager/config_manager_test.cc @@ -30,8 +30,8 @@ class ConfigManagerTest : public testing::Test { ConfigManagerTest() : config_manager_(NULL) {} virtual ~ConfigManagerTest() {} virtual void SetUp() { - char cybertron_path[80] = "CYBERTRON_PATH="; - putenv(cybertron_path); + char cyber_path[80] = "CYBER_PATH="; + putenv(cyber_path); char module_path[80] = "MODULE_PATH="; putenv(module_path); FLAGS_config_manager_path = "/apollo/modules/perception/testdata/lib/conf"; diff --git a/modules/perception/lib/io/BUILD b/modules/perception/lib/io/BUILD index e7dd2a7f9cf..469fc9d1cbb 100644 --- a/modules/perception/lib/io/BUILD +++ b/modules/perception/lib/io/BUILD @@ -15,7 +15,7 @@ cc_library( "-lboost_system", ], deps = [ - "//cybertron", + "//cyber", "//modules/perception/lib/utils:perception_string_util", ], ) diff --git a/modules/perception/lib/io/file_util.cc b/modules/perception/lib/io/file_util.cc index 760e514242d..f216178f589 100644 --- a/modules/perception/lib/io/file_util.cc +++ b/modules/perception/lib/io/file_util.cc @@ -28,7 +28,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/lib/utils/string_util.h" namespace apollo { diff --git a/modules/perception/lib/registerer/BUILD b/modules/perception/lib/registerer/BUILD index d2248d20057..e872e80f54f 100644 --- a/modules/perception/lib/registerer/BUILD +++ b/modules/perception/lib/registerer/BUILD @@ -7,7 +7,7 @@ cc_library( srcs = ["registerer.cc"], hdrs = ["registerer.h"], deps = [ - "//cybertron", + "//cyber", ], ) diff --git a/modules/perception/lib/registerer/registerer.h b/modules/perception/lib/registerer/registerer.h index afba1a8186c..926588b47d9 100644 --- a/modules/perception/lib/registerer/registerer.h +++ b/modules/perception/lib/registerer/registerer.h @@ -20,7 +20,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace perception { diff --git a/modules/perception/lib/singleton/BUILD b/modules/perception/lib/singleton/BUILD index f448ef06053..8c4c3acacc6 100644 --- a/modules/perception/lib/singleton/BUILD +++ b/modules/perception/lib/singleton/BUILD @@ -7,7 +7,7 @@ cc_library( srcs = [], hdrs = ["singleton.h"], deps = [ - "//cybertron", + "//cyber", ], ) diff --git a/modules/perception/lib/thread/BUILD b/modules/perception/lib/thread/BUILD index 0b6fe7a3779..35ab30f6b1d 100644 --- a/modules/perception/lib/thread/BUILD +++ b/modules/perception/lib/thread/BUILD @@ -17,7 +17,7 @@ cc_library( "thread.h", ], deps = [ - "//cybertron", + "//cyber", ], ) diff --git a/modules/perception/lib/thread/concurrent_queue_test.cc b/modules/perception/lib/thread/concurrent_queue_test.cc index 3d07f0fe2ee..83e93d8e8f2 100644 --- a/modules/perception/lib/thread/concurrent_queue_test.cc +++ b/modules/perception/lib/thread/concurrent_queue_test.cc @@ -15,7 +15,7 @@ *****************************************************************************/ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/lib/thread/concurrent_queue.h" #include "modules/perception/lib/thread/thread.h" diff --git a/modules/perception/lib/thread/thread.cc b/modules/perception/lib/thread/thread.cc index b0bf810edaa..1a595118348 100644 --- a/modules/perception/lib/thread/thread.cc +++ b/modules/perception/lib/thread/thread.cc @@ -17,7 +17,7 @@ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace perception { diff --git a/modules/perception/lib/thread/thread_pool_test.cc b/modules/perception/lib/thread/thread_pool_test.cc index d43ee88a92e..dc59d521b52 100644 --- a/modules/perception/lib/thread/thread_pool_test.cc +++ b/modules/perception/lib/thread/thread_pool_test.cc @@ -16,7 +16,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/lib/thread/concurrent_queue.h" #include "modules/perception/lib/thread/thread_pool.h" diff --git a/modules/perception/lib/utils/BUILD b/modules/perception/lib/utils/BUILD index 70c2f0a5117..3a3ff9690ee 100644 --- a/modules/perception/lib/utils/BUILD +++ b/modules/perception/lib/utils/BUILD @@ -21,7 +21,7 @@ cc_library( srcs = ["timer.cc"], hdrs = ["timer.h"], deps = [ - "//cybertron", + "//cyber", ":perception_perf", ], ) @@ -56,7 +56,7 @@ cc_library( srcs = ["string_util.cc"], hdrs = ["string_util.h"], deps = [ - "//cybertron", + "//cyber", ], ) diff --git a/modules/perception/lib/utils/string_util.cc b/modules/perception/lib/utils/string_util.cc index cf18007eb8d..6732689018c 100644 --- a/modules/perception/lib/utils/string_util.cc +++ b/modules/perception/lib/utils/string_util.cc @@ -17,7 +17,7 @@ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace perception { diff --git a/modules/perception/lib/utils/timer.cc b/modules/perception/lib/utils/timer.cc index c2cb50fc87c..cb78b10cf5e 100644 --- a/modules/perception/lib/utils/timer.cc +++ b/modules/perception/lib/utils/timer.cc @@ -16,7 +16,7 @@ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/lib/utils/timer.h" namespace apollo { diff --git a/modules/perception/lidar/app/BUILD b/modules/perception/lidar/app/BUILD index 305dfc37191..dc23de5c1d2 100644 --- a/modules/perception/lidar/app/BUILD +++ b/modules/perception/lidar/app/BUILD @@ -19,7 +19,7 @@ cc_library( "lidar_obstacle_segmentation.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/common/proto:error_code_proto", "//modules/common/proto:header_proto", "//modules/drivers/proto:sensor_proto", @@ -44,7 +44,7 @@ cc_library( "lidar_obstacle_tracking.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/common/util", "//modules/perception/base", "//modules/perception/lib/config_manager", diff --git a/modules/perception/lidar/app/lidar_app_lidar_pipeline_test.cc b/modules/perception/lidar/app/lidar_app_lidar_pipeline_test.cc index ea978fb90bb..abe69c980db 100644 --- a/modules/perception/lidar/app/lidar_app_lidar_pipeline_test.cc +++ b/modules/perception/lidar/app/lidar_app_lidar_pipeline_test.cc @@ -34,8 +34,8 @@ namespace lidar { class LidarAppPipelineTest : public testing::Test { protected: void SetUp() { - char cybertron_path[100] = "CYBERTRON_PATH="; - putenv(cybertron_path); + char cyber_path[100] = "CYBER_PATH="; + putenv(cyber_path); char module_path[100] = "MODULE_PATH="; putenv(module_path); FLAGS_work_root = "/apollo/modules/perception/testdata/lidar/app"; diff --git a/modules/perception/lidar/common/BUILD b/modules/perception/lidar/common/BUILD index 0b94428b841..7e727aa5c68 100644 --- a/modules/perception/lidar/common/BUILD +++ b/modules/perception/lidar/common/BUILD @@ -47,7 +47,7 @@ cc_library( "lidar_log.h", ], deps = [ - "//cybertron", + "//cyber", ], ) @@ -57,7 +57,7 @@ cc_library( "feature_descriptor.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/perception/base:point_cloud", ], ) @@ -133,7 +133,7 @@ cc_library( "object_sequence.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/perception/base:object", "//modules/perception/lidar/common", ], diff --git a/modules/perception/lidar/common/lidar_log.h b/modules/perception/lidar/common/lidar_log.h index cb951ea926f..e5e4142cee2 100644 --- a/modules/perception/lidar/common/lidar_log.h +++ b/modules/perception/lidar/common/lidar_log.h @@ -15,7 +15,7 @@ *****************************************************************************/ #pragma once -#include "cybertron/common/log.h" +#include "cyber/common/log.h" // 100-199 reserve for hd lidar(64...) module error #define HDLIDAR_SOURCE_DATA_ERROR 100 diff --git a/modules/perception/lidar/common/object_sequence.cc b/modules/perception/lidar/common/object_sequence.cc index ec404b06c4e..8f9d61baec3 100644 --- a/modules/perception/lidar/common/object_sequence.cc +++ b/modules/perception/lidar/common/object_sequence.cc @@ -17,7 +17,7 @@ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace perception { diff --git a/modules/perception/lidar/lib/classifier/fused_classifier/BUILD b/modules/perception/lidar/lib/classifier/fused_classifier/BUILD index 1b96e6c9d48..fde433153c3 100644 --- a/modules/perception/lidar/lib/classifier/fused_classifier/BUILD +++ b/modules/perception/lidar/lib/classifier/fused_classifier/BUILD @@ -11,7 +11,7 @@ cc_library( "util.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/perception/base:object", "@eigen", ], @@ -40,7 +40,7 @@ cc_library( deps = [ ":type_fusion_interface", ":util", - "//cybertron", + "//cyber", "//modules/common/util:file_util", "//modules/perception/base:object", "//modules/perception/base:point_cloud", @@ -61,7 +61,7 @@ cc_library( ], deps = [ ":type_fusion_interface", - "//cybertron", + "//cyber", "//modules/common/util:file_util", "//modules/perception/lib/config_manager", "//modules/perception/lib/io:file_util", diff --git a/modules/perception/lidar/lib/classifier/fused_classifier/ccrf_type_fusion.cc b/modules/perception/lidar/lib/classifier/fused_classifier/ccrf_type_fusion.cc index b669d74ae6c..6b9ce4f7ce8 100644 --- a/modules/perception/lidar/lib/classifier/fused_classifier/ccrf_type_fusion.cc +++ b/modules/perception/lidar/lib/classifier/fused_classifier/ccrf_type_fusion.cc @@ -18,7 +18,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/util/file.h" #include "modules/perception/base/object_types.h" #include "modules/perception/base/point_cloud.h" diff --git a/modules/perception/lidar/lib/classifier/fused_classifier/fused_classifier_test.cc b/modules/perception/lidar/lib/classifier/fused_classifier/fused_classifier_test.cc index 98e7b84b9c4..4181ff9df77 100644 --- a/modules/perception/lidar/lib/classifier/fused_classifier/fused_classifier_test.cc +++ b/modules/perception/lidar/lib/classifier/fused_classifier/fused_classifier_test.cc @@ -36,8 +36,8 @@ using base::ObjectPtr; class FusedClassifierTest : public testing::Test { protected: void SetUp() override { - char cybertron_path[80] = "CYBERTRON_PATH="; - putenv(cybertron_path); + char cyber_path[80] = "CYBER_PATH="; + putenv(cyber_path); char module_path[80] = "MODULE_PATH="; putenv(module_path); FLAGS_work_root = "/apollo/modules/perception/testdata/" diff --git a/modules/perception/lidar/lib/classifier/fused_classifier/util.cc b/modules/perception/lidar/lib/classifier/fused_classifier/util.cc index 1e946c1628d..655c8347e2f 100644 --- a/modules/perception/lidar/lib/classifier/fused_classifier/util.cc +++ b/modules/perception/lidar/lib/classifier/fused_classifier/util.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ #include "modules/perception/lidar/lib/classifier/fused_classifier/util.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace perception { diff --git a/modules/perception/lidar/lib/dummy/BUILD b/modules/perception/lidar/lib/dummy/BUILD index 830ab65e955..d165cfcb9cc 100644 --- a/modules/perception/lidar/lib/dummy/BUILD +++ b/modules/perception/lidar/lib/dummy/BUILD @@ -21,7 +21,7 @@ cc_library( "dummy_segmentation.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/perception/base", "//modules/perception/common/point_cloud_processing", "//modules/perception/lib/registerer", diff --git a/modules/perception/lidar/lib/ground_detector/ground_service_detector/BUILD b/modules/perception/lidar/lib/ground_detector/ground_service_detector/BUILD index 0c30faa57a3..33f43787c74 100644 --- a/modules/perception/lidar/lib/ground_detector/ground_service_detector/BUILD +++ b/modules/perception/lidar/lib/ground_detector/ground_service_detector/BUILD @@ -12,7 +12,7 @@ cc_library( ], deps = [ "@eigen", - "//cybertron", + "//cyber", "//modules/common/util", "//modules/perception/base:base_type", "//modules/perception/lib/config_manager", diff --git a/modules/perception/lidar/lib/ground_detector/ground_service_detector/ground_service_detector_test.cc b/modules/perception/lidar/lib/ground_detector/ground_service_detector/ground_service_detector_test.cc index 3d5de460f89..aec50526364 100644 --- a/modules/perception/lidar/lib/ground_detector/ground_service_detector/ground_service_detector_test.cc +++ b/modules/perception/lidar/lib/ground_detector/ground_service_detector/ground_service_detector_test.cc @@ -30,8 +30,8 @@ namespace lidar { class LidarLibGroundServiceDetectorTest : public testing::Test { protected: void SetUp() { - char cybertron_path[] = "CYBERTRON_PATH="; - putenv(cybertron_path); + char cyber_path[] = "CYBER_PATH="; + putenv(cyber_path); char module_path[] = "MODULE_PATH="; putenv(module_path); FLAGS_work_root = "/apollo/modules/perception/testdata/" diff --git a/modules/perception/lidar/lib/ground_detector/spatio_temporal_ground_detector/BUILD b/modules/perception/lidar/lib/ground_detector/spatio_temporal_ground_detector/BUILD index 8484b790da6..a5db48304dd 100644 --- a/modules/perception/lidar/lib/ground_detector/spatio_temporal_ground_detector/BUILD +++ b/modules/perception/lidar/lib/ground_detector/spatio_temporal_ground_detector/BUILD @@ -13,7 +13,7 @@ cc_library( copts = ["-msse4.1"], deps = [ "@eigen", - "//cybertron", + "//cyber", "//modules/perception/base", "//modules/perception/lib/registerer", "//modules/perception/lib/singleton", diff --git a/modules/perception/lidar/lib/ground_detector/spatio_temporal_ground_detector/spatio_temporal_ground_detector_test.cc b/modules/perception/lidar/lib/ground_detector/spatio_temporal_ground_detector/spatio_temporal_ground_detector_test.cc index d90d2f24559..989f7b61900 100644 --- a/modules/perception/lidar/lib/ground_detector/spatio_temporal_ground_detector/spatio_temporal_ground_detector_test.cc +++ b/modules/perception/lidar/lib/ground_detector/spatio_temporal_ground_detector/spatio_temporal_ground_detector_test.cc @@ -58,8 +58,8 @@ bool LoadPCDFile(const std::string& file_path, base::PointFCloudPtr cloud_out) { } TEST(SpatioTemporalGroundDetectorTest, test_spatio_temporal_ground_detector) { - // char cybertron_path[100] = "CYBERTRON_PATH="; - // putenv(cybertron_path); + // char cyber_path[100] = "CYBER_PATH="; + // putenv(cyber_path); // char module_path[100] = "MODULE_PATH="; // putenv(module_path); // EXPECT_TRUE(SceneManager::Instance().Init()); diff --git a/modules/perception/lidar/lib/interface/base_bipartite_graph_matcher.h b/modules/perception/lidar/lib/interface/base_bipartite_graph_matcher.h index ec1c49d12b8..48e1102a9cc 100644 --- a/modules/perception/lidar/lib/interface/base_bipartite_graph_matcher.h +++ b/modules/perception/lidar/lib/interface/base_bipartite_graph_matcher.h @@ -21,7 +21,7 @@ #include "Eigen/Core" -#include "cybertron/common/macros.h" +#include "cyber/common/macros.h" #include "modules/perception/common/graph/secure_matrix.h" #include "modules/perception/lib/registerer/registerer.h" diff --git a/modules/perception/lidar/lib/interface/base_classifier.h b/modules/perception/lidar/lib/interface/base_classifier.h index 1699963c4c8..fba0bdbb131 100644 --- a/modules/perception/lidar/lib/interface/base_classifier.h +++ b/modules/perception/lidar/lib/interface/base_classifier.h @@ -18,7 +18,7 @@ #include #include -#include "cybertron/common/macros.h" +#include "cyber/common/macros.h" #include "modules/perception/lib/registerer/registerer.h" #include "modules/perception/lidar/common/lidar_frame.h" diff --git a/modules/perception/lidar/lib/interface/base_ground_detector.h b/modules/perception/lidar/lib/interface/base_ground_detector.h index 4c2b9139666..ccc18717e59 100644 --- a/modules/perception/lidar/lib/interface/base_ground_detector.h +++ b/modules/perception/lidar/lib/interface/base_ground_detector.h @@ -17,7 +17,7 @@ #include -#include "cybertron/common/macros.h" +#include "cyber/common/macros.h" #include "modules/perception/lib/registerer/registerer.h" #include "modules/perception/lidar/common/lidar_frame.h" diff --git a/modules/perception/lidar/lib/interface/base_multi_target_tracker.h b/modules/perception/lidar/lib/interface/base_multi_target_tracker.h index 15913655c98..5a00fdfad09 100644 --- a/modules/perception/lidar/lib/interface/base_multi_target_tracker.h +++ b/modules/perception/lidar/lib/interface/base_multi_target_tracker.h @@ -18,7 +18,7 @@ #include #include -#include "cybertron/common/macros.h" +#include "cyber/common/macros.h" #include "modules/perception/lib/registerer/registerer.h" #include "modules/perception/lidar/common/lidar_frame.h" diff --git a/modules/perception/lidar/lib/interface/base_object_filter.h b/modules/perception/lidar/lib/interface/base_object_filter.h index df860eee0a0..a65bf914570 100644 --- a/modules/perception/lidar/lib/interface/base_object_filter.h +++ b/modules/perception/lidar/lib/interface/base_object_filter.h @@ -18,7 +18,7 @@ #include #include -#include "cybertron/common/macros.h" +#include "cyber/common/macros.h" #include "modules/perception/lib/registerer/registerer.h" #include "modules/perception/lidar/common/lidar_frame.h" diff --git a/modules/perception/lidar/lib/interface/base_roi_filter.h b/modules/perception/lidar/lib/interface/base_roi_filter.h index db1e4cab3f3..ec548b2739d 100644 --- a/modules/perception/lidar/lib/interface/base_roi_filter.h +++ b/modules/perception/lidar/lib/interface/base_roi_filter.h @@ -18,7 +18,7 @@ #include #include -#include "cybertron/common/macros.h" +#include "cyber/common/macros.h" #include "modules/perception/lib/registerer/registerer.h" #include "modules/perception/lidar/common/lidar_frame.h" diff --git a/modules/perception/lidar/lib/interface/base_segmentation.h b/modules/perception/lidar/lib/interface/base_segmentation.h index 43d0d69d133..5071f5efa22 100644 --- a/modules/perception/lidar/lib/interface/base_segmentation.h +++ b/modules/perception/lidar/lib/interface/base_segmentation.h @@ -18,7 +18,7 @@ #include #include -#include "cybertron/common/macros.h" +#include "cyber/common/macros.h" #include "modules/perception/lib/registerer/registerer.h" #include "modules/perception/lidar/common/lidar_frame.h" diff --git a/modules/perception/lidar/lib/map_manager/BUILD b/modules/perception/lidar/lib/map_manager/BUILD index 11062f0ad7d..a0a153a1798 100644 --- a/modules/perception/lidar/lib/map_manager/BUILD +++ b/modules/perception/lidar/lib/map_manager/BUILD @@ -11,7 +11,7 @@ cc_library( "map_manager.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/common/util:file_util", "//modules/perception/base:base_type", "//modules/perception/lib/config_manager", diff --git a/modules/perception/lidar/lib/map_manager/map_manager.cc b/modules/perception/lidar/lib/map_manager/map_manager.cc index bb632011daa..9f64e14487d 100644 --- a/modules/perception/lidar/lib/map_manager/map_manager.cc +++ b/modules/perception/lidar/lib/map_manager/map_manager.cc @@ -15,7 +15,7 @@ *****************************************************************************/ #include "modules/perception/lidar/lib/map_manager/map_manager.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/proto/map_manager_config.pb.h" diff --git a/modules/perception/lidar/lib/map_manager/map_manager_test.cc b/modules/perception/lidar/lib/map_manager/map_manager_test.cc index dcadb348986..7fe0663ac60 100644 --- a/modules/perception/lidar/lib/map_manager/map_manager_test.cc +++ b/modules/perception/lidar/lib/map_manager/map_manager_test.cc @@ -25,8 +25,8 @@ namespace perception { namespace lidar { TEST(LidarLibMapManagerTest, lidar_map_manager_empty_test) { - char cybertron_path[100] = "CYBERTRON_PATH="; - putenv(cybertron_path); + char cyber_path[100] = "CYBER_PATH="; + putenv(cyber_path); char module_path[100] = "MODULE_PATH="; putenv(module_path); @@ -45,8 +45,8 @@ TEST(LidarLibMapManagerTest, lidar_map_manager_empty_test) { } TEST(LidarLibMapManagerTest, lidar_map_manager_test) { - char cybertron_path[100] = "CYBERTRON_PATH="; - putenv(cybertron_path); + char cyber_path[100] = "CYBER_PATH="; + putenv(cyber_path); char module_path[100] = "MODULE_PATH="; putenv(module_path); diff --git a/modules/perception/lidar/lib/object_filter_bank/BUILD b/modules/perception/lidar/lib/object_filter_bank/BUILD index 2a05aed9d30..8bfbab4e390 100644 --- a/modules/perception/lidar/lib/object_filter_bank/BUILD +++ b/modules/perception/lidar/lib/object_filter_bank/BUILD @@ -12,7 +12,7 @@ cc_library( ], deps = [ "@eigen", - "//cybertron", + "//cyber", "//modules/common/util", "//modules/perception/base", "//modules/perception/lib/config_manager", diff --git a/modules/perception/lidar/lib/object_filter_bank/object_filter_bank.h b/modules/perception/lidar/lib/object_filter_bank/object_filter_bank.h index 909ec4a1c49..1805d21596b 100644 --- a/modules/perception/lidar/lib/object_filter_bank/object_filter_bank.h +++ b/modules/perception/lidar/lib/object_filter_bank/object_filter_bank.h @@ -17,7 +17,7 @@ #include #include -#include "cybertron/common/macros.h" +#include "cyber/common/macros.h" #include "modules/perception/lidar/lib/interface/base_object_filter.h" namespace apollo { diff --git a/modules/perception/lidar/lib/object_filter_bank/object_filter_bank_test.cc b/modules/perception/lidar/lib/object_filter_bank/object_filter_bank_test.cc index 13777c59ce0..2b7ef17a535 100644 --- a/modules/perception/lidar/lib/object_filter_bank/object_filter_bank_test.cc +++ b/modules/perception/lidar/lib/object_filter_bank/object_filter_bank_test.cc @@ -65,8 +65,8 @@ TEST(LidarLibObjectFilterBankTest, lidar_lib_object_filter_bank_test) { // FIXME(perception): fix missing data files return; - char cybertron_path[100] = "CYBERTRON_PATH="; - putenv(cybertron_path); + char cyber_path[100] = "CYBER_PATH="; + putenv(cyber_path); char module_path[100] = "MODULE_PATH="; putenv(module_path); FLAGS_work_root = "/apollo/modules/perception/testdata/" diff --git a/modules/perception/lidar/lib/object_filter_bank/roi_boundary_filter/BUILD b/modules/perception/lidar/lib/object_filter_bank/roi_boundary_filter/BUILD index c149418355c..3acaf6f8de7 100644 --- a/modules/perception/lidar/lib/object_filter_bank/roi_boundary_filter/BUILD +++ b/modules/perception/lidar/lib/object_filter_bank/roi_boundary_filter/BUILD @@ -18,7 +18,7 @@ cc_library( "//modules/perception/lib/config_manager:config_manager", "//modules/perception/lib/io:file_util", "//modules/perception/lidar/lib/interface:base_object_filter", - "//cybertron", + "//cyber", "@eigen", ], ) diff --git a/modules/perception/lidar/lib/object_filter_bank/roi_boundary_filter/roi_boundary_filter.cc b/modules/perception/lidar/lib/object_filter_bank/roi_boundary_filter/roi_boundary_filter.cc index da2ef465be1..0f8388987d6 100644 --- a/modules/perception/lidar/lib/object_filter_bank/roi_boundary_filter/roi_boundary_filter.cc +++ b/modules/perception/lidar/lib/object_filter_bank/roi_boundary_filter/roi_boundary_filter.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ #include "modules/perception/lidar/lib/object_filter_bank/roi_boundary_filter/roi_boundary_filter.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/common/geometry/common.h" #include "modules/perception/lib/config_manager/config_manager.h" #include "modules/perception/lib/io/file_util.h" diff --git a/modules/perception/lidar/lib/object_filter_bank/roi_boundary_filter/roi_boundary_filter_test.cc b/modules/perception/lidar/lib/object_filter_bank/roi_boundary_filter/roi_boundary_filter_test.cc index d39fda0d7a3..571902c4b65 100644 --- a/modules/perception/lidar/lib/object_filter_bank/roi_boundary_filter/roi_boundary_filter_test.cc +++ b/modules/perception/lidar/lib/object_filter_bank/roi_boundary_filter/roi_boundary_filter_test.cc @@ -27,8 +27,8 @@ namespace lidar { class ROIBoundaryFilterTest : public testing::Test { protected: void SetUp() { - char cybertron_path[100] = "CYBERTRON_PATH="; - putenv(cybertron_path); + char cyber_path[100] = "CYBER_PATH="; + putenv(cyber_path); char module_path[100] = "MODULE_PATH="; putenv(module_path); FLAGS_work_root = diff --git a/modules/perception/lidar/lib/pointcloud_preprocessor/BUILD b/modules/perception/lidar/lib/pointcloud_preprocessor/BUILD index 11c08c73a5c..1b35086304a 100644 --- a/modules/perception/lidar/lib/pointcloud_preprocessor/BUILD +++ b/modules/perception/lidar/lib/pointcloud_preprocessor/BUILD @@ -11,7 +11,7 @@ cc_library( "pointcloud_preprocessor.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/common/proto:error_code_proto", "//modules/common/proto:header_proto", "//modules/common/util", diff --git a/modules/perception/lidar/lib/pointcloud_preprocessor/pointcloud_preprocessor_test.cc b/modules/perception/lidar/lib/pointcloud_preprocessor/pointcloud_preprocessor_test.cc index c84e2438843..6490eb2eb3e 100644 --- a/modules/perception/lidar/lib/pointcloud_preprocessor/pointcloud_preprocessor_test.cc +++ b/modules/perception/lidar/lib/pointcloud_preprocessor/pointcloud_preprocessor_test.cc @@ -25,8 +25,8 @@ namespace lidar { class PointCloudPreprocessorTest : public testing::Test { protected: void SetUp() { - char cybertron_path[100] = "CYBERTRON_PATH="; - putenv(cybertron_path); + char cyber_path[100] = "CYBER_PATH="; + putenv(cyber_path); char module_path[100] = "MODULE_PATH="; putenv(module_path); FLAGS_work_root = "/apollo/modules/perception/testdata/" diff --git a/modules/perception/lidar/lib/roi_filter/hdmap_roi_filter/BUILD b/modules/perception/lidar/lib/roi_filter/hdmap_roi_filter/BUILD index b93c170d707..ef586f7b1c3 100644 --- a/modules/perception/lidar/lib/roi_filter/hdmap_roi_filter/BUILD +++ b/modules/perception/lidar/lib/roi_filter/hdmap_roi_filter/BUILD @@ -11,7 +11,7 @@ cc_library( "bitmap2d.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/perception/lidar/common:lidar_log", "@eigen", ], @@ -29,7 +29,7 @@ cc_library( ":bitmap2d", ":polygon_mask", ":polygon_scan_cvter", - "//cybertron", + "//cyber", "//modules/perception/base:point_cloud", "//modules/perception/lidar/common:lidar_point_label", "//modules/perception/lidar/lib/interface:base_object_filter", diff --git a/modules/perception/lidar/lib/roi_filter/hdmap_roi_filter/hdmap_roi_filter_test.cc b/modules/perception/lidar/lib/roi_filter/hdmap_roi_filter/hdmap_roi_filter_test.cc index 7a0d749ea28..ba5257cffc4 100644 --- a/modules/perception/lidar/lib/roi_filter/hdmap_roi_filter/hdmap_roi_filter_test.cc +++ b/modules/perception/lidar/lib/roi_filter/hdmap_roi_filter/hdmap_roi_filter_test.cc @@ -169,8 +169,8 @@ class HdmapROIFilterTest : public ::testing::Test { public: HdmapROIFilterTest() : hdmap_roi_filter_ptr_(new HdmapROIFilter) { // prepare test data - char cybertron_path[50] = "CYBERTRON_PATH="; - putenv(cybertron_path); + char cyber_path[50] = "CYBER_PATH="; + putenv(cyber_path); char module_path[50] = "MODULE_PATH="; putenv(module_path); FLAGS_work_root = "/apollo/modules/perception/testdata/" diff --git a/modules/perception/lidar/lib/roi_filter/roi_service_filter/BUILD b/modules/perception/lidar/lib/roi_filter/roi_service_filter/BUILD index 6f418456ac4..4c957d8ed06 100644 --- a/modules/perception/lidar/lib/roi_filter/roi_service_filter/BUILD +++ b/modules/perception/lidar/lib/roi_filter/roi_service_filter/BUILD @@ -11,7 +11,7 @@ cc_library( "roi_service_filter.h", ], deps = [ - "//cybertron", + "//cyber", "//modules/perception/base:base_type", "//modules/perception/base:blob", "//modules/perception/base:box", diff --git a/modules/perception/lidar/lib/roi_filter/roi_service_filter/roi_service_filter_test.cc b/modules/perception/lidar/lib/roi_filter/roi_service_filter/roi_service_filter_test.cc index b657396bbb1..fa40f0193d3 100644 --- a/modules/perception/lidar/lib/roi_filter/roi_service_filter/roi_service_filter_test.cc +++ b/modules/perception/lidar/lib/roi_filter/roi_service_filter/roi_service_filter_test.cc @@ -42,8 +42,8 @@ namespace lidar { class LidarLibROIServiceFilterTest : public testing::Test { protected: void SetUp() { - char cybertron_path[100] = "CYBERTRON_PATH="; - putenv(cybertron_path); + char cyber_path[100] = "CYBER_PATH="; + putenv(cyber_path); char module_path[100] = "MODULE_PATH="; putenv(module_path); FLAGS_work_root = "/apollo/modules/perception/testdata/" diff --git a/modules/perception/lidar/lib/scene_manager/scene_manager_test.cc b/modules/perception/lidar/lib/scene_manager/scene_manager_test.cc index 548b57210ad..bc47d616d5b 100644 --- a/modules/perception/lidar/lib/scene_manager/scene_manager_test.cc +++ b/modules/perception/lidar/lib/scene_manager/scene_manager_test.cc @@ -38,8 +38,8 @@ namespace lidar { class LidarLibSceneManagerTest : public testing::Test { protected: void SetUp() { - char cybertron_path[] = "CYBERTRON_PATH="; - putenv(cybertron_path); + char cyber_path[] = "CYBER_PATH="; + putenv(cyber_path); char module_path[] = "MODULE_PATH="; putenv(module_path); FLAGS_work_root = diff --git a/modules/perception/lidar/lib/scene_manager/scene_service.h b/modules/perception/lidar/lib/scene_manager/scene_service.h index bc1db682094..c3d4ba2e98d 100644 --- a/modules/perception/lidar/lib/scene_manager/scene_service.h +++ b/modules/perception/lidar/lib/scene_manager/scene_service.h @@ -19,7 +19,7 @@ #include #include -#include "cybertron/common/macros.h" +#include "cyber/common/macros.h" #include "modules/perception/lib/registerer/registerer.h" namespace apollo { diff --git a/modules/perception/lidar/lib/segmentation/cnnseg/BUILD b/modules/perception/lidar/lib/segmentation/cnnseg/BUILD index 88641df6d98..14001fc3bb1 100644 --- a/modules/perception/lidar/lib/segmentation/cnnseg/BUILD +++ b/modules/perception/lidar/lib/segmentation/cnnseg/BUILD @@ -15,7 +15,7 @@ cc_library( ":feature_generator", ":disjoint_set", ":util", - "//cybertron", + "//cyber", "//modules/common/util:file_util", "//modules/common/util:string_util", "//modules/perception/base", diff --git a/modules/perception/lidar/lib/segmentation/cnnseg/cnn_segmentation.cc b/modules/perception/lidar/lib/segmentation/cnnseg/cnn_segmentation.cc index 9a7a58a2284..9d261570dfe 100644 --- a/modules/perception/lidar/lib/segmentation/cnnseg/cnn_segmentation.cc +++ b/modules/perception/lidar/lib/segmentation/cnnseg/cnn_segmentation.cc @@ -15,7 +15,7 @@ *****************************************************************************/ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/lidar/lib/segmentation/cnnseg/proto/cnnseg_config.pb.h" diff --git a/modules/perception/lidar/lib/segmentation/cnnseg/cnn_segmentation_test.cc b/modules/perception/lidar/lib/segmentation/cnnseg/cnn_segmentation_test.cc index e0912ce2477..b36ef69de73 100644 --- a/modules/perception/lidar/lib/segmentation/cnnseg/cnn_segmentation_test.cc +++ b/modules/perception/lidar/lib/segmentation/cnnseg/cnn_segmentation_test.cc @@ -68,8 +68,8 @@ void PrintObjects(const std::vector& objects) { /* * TODO(perception): enable this test. TEST(CNNSegmentationTest, cnn_segmentation_sequence_test) { - char cybertron_path[100] = "CYBERTRON_PATH="; - putenv(cybertron_path); + char cyber_path[100] = "CYBER_PATH="; + putenv(cyber_path); char module_path[100] = "MODULE_PATH="; putenv(module_path); FLAGS_work_root = "/apollo/modules/perception/testdata/" @@ -116,8 +116,8 @@ TEST(CNNSegmentationTest, cnn_segmentation_sequence_test) { } TEST(CNNSegmentationTest, cnn_segmentation_test) { - char cybertron_path[100] = "CYBERTRON_PATH="; - putenv(cybertron_path); + char cyber_path[100] = "CYBER_PATH="; + putenv(cyber_path); char module_path[100] = "MODULE_PATH="; putenv(module_path); FLAGS_work_root = "/apollo/modules/perception/testdata/" diff --git a/modules/perception/lidar/lib/segmentation/cnnseg/feature_generator_test.cc b/modules/perception/lidar/lib/segmentation/cnnseg/feature_generator_test.cc index a419eccbcc4..ed5cc054568 100644 --- a/modules/perception/lidar/lib/segmentation/cnnseg/feature_generator_test.cc +++ b/modules/perception/lidar/lib/segmentation/cnnseg/feature_generator_test.cc @@ -114,8 +114,8 @@ class FeatureGeneratorTest : public ::testing::Test { }; TEST_F(FeatureGeneratorTest, basic_test) { - char cybertron_path[100] = "CYBERTRON_PATH="; - putenv(cybertron_path); + char cyber_path[100] = "CYBER_PATH="; + putenv(cyber_path); char module_path[100] = "MODULE_PATH="; putenv(module_path); FLAGS_work_root = "/apollo/modules/perception/testdata/" diff --git a/modules/perception/lidar/lib/segmentation/cnnseg/spp_engine/BUILD b/modules/perception/lidar/lib/segmentation/cnnseg/spp_engine/BUILD index fa4b34d413c..a970f9991e3 100644 --- a/modules/perception/lidar/lib/segmentation/cnnseg/spp_engine/BUILD +++ b/modules/perception/lidar/lib/segmentation/cnnseg/spp_engine/BUILD @@ -16,7 +16,7 @@ cc_library( ":spp_label_image", ":spp_seg_cc_2d", ":spp_struct", - "//cybertron", + "//cyber", "@eigen", ], ) @@ -100,7 +100,7 @@ cc_library( ], deps = [ ":spp_label_image", - "//cybertron", + "//cyber", "//modules/perception/base", "//modules/perception/common/i_lib", "//modules/perception/lib/thread", diff --git a/modules/perception/lidar/lib/segmentation/cnnseg/spp_engine/spp_cluster_list.h b/modules/perception/lidar/lib/segmentation/cnnseg/spp_engine/spp_cluster_list.h index 077fa53a2e4..c5445cb040c 100644 --- a/modules/perception/lidar/lib/segmentation/cnnseg/spp_engine/spp_cluster_list.h +++ b/modules/perception/lidar/lib/segmentation/cnnseg/spp_engine/spp_cluster_list.h @@ -18,7 +18,7 @@ #include #include -#include "cybertron/common/macros.h" +#include "cyber/common/macros.h" #include "modules/perception/lidar/lib/segmentation/cnnseg/spp_engine/spp_cluster.h" #include "modules/perception/lidar/lib/segmentation/cnnseg/spp_engine/spp_label_image.h" diff --git a/modules/perception/lidar/lib/segmentation/cnnseg/spp_engine/spp_label_image.h b/modules/perception/lidar/lib/segmentation/cnnseg/spp_engine/spp_label_image.h index dda44cf39c1..a3a0684704f 100644 --- a/modules/perception/lidar/lib/segmentation/cnnseg/spp_engine/spp_label_image.h +++ b/modules/perception/lidar/lib/segmentation/cnnseg/spp_engine/spp_label_image.h @@ -21,7 +21,7 @@ #include "gtest/gtest_prod.h" -#include "cybertron/common/macros.h" +#include "cyber/common/macros.h" #include "modules/perception/common/i_lib/core/i_alloc.h" #include "modules/perception/lidar/lib/segmentation/cnnseg/spp_engine/spp_cluster.h" diff --git a/modules/perception/lidar/lib/tracker/association/BUILD b/modules/perception/lidar/lib/tracker/association/BUILD index 4f973335cb0..e4fd3ed2f12 100644 --- a/modules/perception/lidar/lib/tracker/association/BUILD +++ b/modules/perception/lidar/lib/tracker/association/BUILD @@ -14,7 +14,7 @@ cc_library( "//modules/perception/common/graph:gated_hungarian_bigraph_matcher", "//modules/perception/common/graph:secure_matrix", "//modules/perception/lidar/lib/interface:base_bipartite_graph_matcher", - "//cybertron", + "//cyber", "@eigen", ], @@ -32,7 +32,7 @@ cc_library( "//modules/perception/common/graph:gated_hungarian_bigraph_matcher", "//modules/perception/common/graph:secure_matrix", "//modules/perception/lidar/lib/interface:base_bipartite_graph_matcher", - "//cybertron", + "//cyber", ], ) diff --git a/modules/perception/lidar/lib/tracker/association/distance_collection.cc b/modules/perception/lidar/lib/tracker/association/distance_collection.cc index d5a854242a7..b92a84b0538 100644 --- a/modules/perception/lidar/lib/tracker/association/distance_collection.cc +++ b/modules/perception/lidar/lib/tracker/association/distance_collection.cc @@ -15,7 +15,7 @@ *****************************************************************************/ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/common/geometry/common.h" #include "modules/perception/common/geometry/basic.h" diff --git a/modules/perception/lidar/lib/tracker/association/gnn_bipartite_graph_matcher.cc b/modules/perception/lidar/lib/tracker/association/gnn_bipartite_graph_matcher.cc index a7498581386..5b1c29515dc 100644 --- a/modules/perception/lidar/lib/tracker/association/gnn_bipartite_graph_matcher.cc +++ b/modules/perception/lidar/lib/tracker/association/gnn_bipartite_graph_matcher.cc @@ -19,7 +19,7 @@ #include #include #include "modules/perception/lidar/lib/tracker/association/gnn_bipartite_graph_matcher.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { diff --git a/modules/perception/lidar/lib/tracker/association/multi_hm_bipartite_graph_matcher.cc b/modules/perception/lidar/lib/tracker/association/multi_hm_bipartite_graph_matcher.cc index ce56efe7ee5..8c22df46015 100644 --- a/modules/perception/lidar/lib/tracker/association/multi_hm_bipartite_graph_matcher.cc +++ b/modules/perception/lidar/lib/tracker/association/multi_hm_bipartite_graph_matcher.cc @@ -17,7 +17,7 @@ #include #include "modules/perception/lidar/lib/tracker/association/multi_hm_bipartite_graph_matcher.h" #include "modules/perception/common/graph/gated_hungarian_bigraph_matcher.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { diff --git a/modules/perception/lidar/lib/tracker/common/BUILD b/modules/perception/lidar/lib/tracker/common/BUILD index d4cf3eaa330..db16b75e1fa 100644 --- a/modules/perception/lidar/lib/tracker/common/BUILD +++ b/modules/perception/lidar/lib/tracker/common/BUILD @@ -16,7 +16,7 @@ cc_library( "//modules/perception/base:point_cloud", "//modules/perception/common/point_cloud_processing:point_cloud_processing", "//modules/perception/lidar/common:feature_descriptor", - "//cybertron", + "//cyber", ], ) @@ -33,7 +33,7 @@ cc_library( deps = [ ":tracked_object", "//modules/perception/base:object_pool", - "//cybertron", + "//cyber", ], ) @@ -50,7 +50,7 @@ cc_library( deps = [ ":track_data", "//modules/perception/base:object_pool", - "//cybertron", + "//cyber", "@eigen", ], ) diff --git a/modules/perception/lidar/lib/tracker/common/mlf_track_data.cc b/modules/perception/lidar/lib/tracker/common/mlf_track_data.cc index 477be4190ad..0f8131b299c 100644 --- a/modules/perception/lidar/lib/tracker/common/mlf_track_data.cc +++ b/modules/perception/lidar/lib/tracker/common/mlf_track_data.cc @@ -16,7 +16,7 @@ #include "modules/perception/lidar/lib/tracker/common/mlf_track_data.h" #include "modules/perception/lidar/lib/tracker/common/track_pool_types.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { diff --git a/modules/perception/lidar/lib/tracker/common/track_data.cc b/modules/perception/lidar/lib/tracker/common/track_data.cc index 0351ab3e334..9ba2d06f2e7 100644 --- a/modules/perception/lidar/lib/tracker/common/track_data.cc +++ b/modules/perception/lidar/lib/tracker/common/track_data.cc @@ -15,7 +15,7 @@ *****************************************************************************/ #include "modules/perception/lidar/lib/tracker/common/track_data.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace perception { diff --git a/modules/perception/lidar/lib/tracker/common/track_pool_types.cc b/modules/perception/lidar/lib/tracker/common/track_pool_types.cc index da317653eee..7e88ca65196 100644 --- a/modules/perception/lidar/lib/tracker/common/track_pool_types.cc +++ b/modules/perception/lidar/lib/tracker/common/track_pool_types.cc @@ -14,7 +14,7 @@ * limitations under the License. *****************************************************************************/ #include "modules/perception/lidar/lib/tracker/common/track_pool_types.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" namespace apollo { namespace perception { diff --git a/modules/perception/lidar/lib/tracker/common/tracked_object.cc b/modules/perception/lidar/lib/tracker/common/tracked_object.cc index dfd8b21a29a..792c25ec738 100644 --- a/modules/perception/lidar/lib/tracker/common/tracked_object.cc +++ b/modules/perception/lidar/lib/tracker/common/tracked_object.cc @@ -18,7 +18,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/base/point_cloud.h" #include "modules/perception/base/point.h" #include "modules/perception/common/point_cloud_processing/common.h" diff --git a/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_base_filter.h b/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_base_filter.h index 04a80114510..af5dece2c17 100644 --- a/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_base_filter.h +++ b/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_base_filter.h @@ -17,7 +17,7 @@ #include -#include "cybertron/common/macros.h" +#include "cyber/common/macros.h" #include "modules/perception/lib/registerer/registerer.h" #include "modules/perception/lidar/lib/tracker/common/tracked_object.h" #include "modules/perception/lidar/lib/tracker/common/mlf_track_data.h" diff --git a/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_motion_measurement.h b/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_motion_measurement.h index ad46a5cebfe..163d7c27b6d 100644 --- a/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_motion_measurement.h +++ b/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_motion_measurement.h @@ -15,7 +15,7 @@ *****************************************************************************/ #pragma once -#include "cybertron/common/macros.h" +#include "cyber/common/macros.h" #include "modules/perception/lidar/lib/tracker/common/mlf_track_data.h" #include "modules/perception/lidar/lib/tracker/common/tracked_object.h" diff --git a/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_track_object_matcher.h b/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_track_object_matcher.h index 2578649bc3e..de5f3a94d33 100644 --- a/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_track_object_matcher.h +++ b/modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_track_object_matcher.h @@ -20,7 +20,7 @@ #include #include -#include "cybertron/common/macros.h" +#include "cyber/common/macros.h" #include "modules/perception/common/graph/secure_matrix.h" #include "modules/perception/lidar/lib/interface/base_bipartite_graph_matcher.h" #include "modules/perception/lidar/lib/tracker/multi_lidar_fusion/mlf_track_object_distance.h" diff --git a/modules/perception/lidar/tools/BUILD b/modules/perception/lidar/tools/BUILD index f1629a81d45..81c14356484 100644 --- a/modules/perception/lidar/tools/BUILD +++ b/modules/perception/lidar/tools/BUILD @@ -6,7 +6,7 @@ cc_binary( name = "offline_lidar_obstacle_perception", srcs = ["offline_lidar_obstacle_perception.cc"], deps = [ - "//cybertron", + "//cyber", "//modules/drivers/proto:sensor_proto", "//modules/map/proto:map_proto", "//modules/perception/base", diff --git a/modules/perception/map/hdmap/hdmap_input.cc b/modules/perception/map/hdmap/hdmap_input.cc index 4dbffa926c1..c4e7554aedf 100644 --- a/modules/perception/map/hdmap/hdmap_input.cc +++ b/modules/perception/map/hdmap/hdmap_input.cc @@ -20,7 +20,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/base/object_pool_types.h" #include "modules/perception/common/geometry/common.h" #include "modules/perception/lib/config_manager/config_manager.h" diff --git a/modules/perception/map/hdmap/hdmap_input_test.cc b/modules/perception/map/hdmap/hdmap_input_test.cc index 180844b7e68..abab5a36b3b 100644 --- a/modules/perception/map/hdmap/hdmap_input_test.cc +++ b/modules/perception/map/hdmap/hdmap_input_test.cc @@ -19,7 +19,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/lib/config_manager/config_manager.h" namespace apollo { @@ -33,8 +33,8 @@ namespace map { class HDMapInputTest : public testing::Test { protected: virtual void SetUp() { - // char* cybertron_path = "CYBERTRON_PATH="; - // putenv(cybertron_path); + // char* cyber_path = "CYBER_PATH="; + // putenv(cyber_path); // char* module_path = "MODULE_PATH="; // putenv(module_path); // FLAGS_config_manager_path = "/apollo/modules/perception/testdata/" diff --git a/modules/perception/onboard/component/BUILD b/modules/perception/onboard/component/BUILD index 62648ae7fc1..f3f4f58d190 100644 --- a/modules/perception/onboard/component/BUILD +++ b/modules/perception/onboard/component/BUILD @@ -36,7 +36,7 @@ cc_library( '-DMODULE_NAME=\\"perception\\"', ], deps = [ - "//cybertron", + "//cyber", "//modules/common/proto:error_code_proto", "//modules/common/proto:geometry_proto", "//modules/common/proto:header_proto", diff --git a/modules/perception/onboard/component/camera_perception_viz_message.h b/modules/perception/onboard/component/camera_perception_viz_message.h index 1e270d40592..bba4a1dc662 100644 --- a/modules/perception/onboard/component/camera_perception_viz_message.h +++ b/modules/perception/onboard/component/camera_perception_viz_message.h @@ -22,7 +22,7 @@ #include #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/common/proto/error_code.pb.h" #include "modules/perception/base/blob.h" #include "modules/perception/base/lane_struct.h" @@ -34,7 +34,7 @@ namespace apollo { namespace perception { namespace onboard { -class CameraPerceptionVizMessage : public cybertron::message::IntraMessage { +class CameraPerceptionVizMessage : public cyber::message::IntraMessage { public: CameraPerceptionVizMessage() { type_name_ = "CameraPerceptionVizMessage"; diff --git a/modules/perception/onboard/component/fusion_camera_detection_component.cc b/modules/perception/onboard/component/fusion_camera_detection_component.cc index fd86b70db79..d5f1561c3da 100644 --- a/modules/perception/onboard/component/fusion_camera_detection_component.cc +++ b/modules/perception/onboard/component/fusion_camera_detection_component.cc @@ -27,7 +27,7 @@ #include #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/common/math/math_utils.h" #include "modules/common/time/time_util.h" #include "modules/common/util/file.h" @@ -46,7 +46,7 @@ namespace onboard { static int GetGpuId(const camera::CameraPerceptionInitOptions &options) { camera::app::PerceptionParam perception_param; std::string work_root = ""; - camera::GetCybertronWorkRoot(&work_root); + camera::GetCyberWorkRoot(&work_root); std::string config_file = lib::FileUtil::GetAbsolutePath(options.root_dir, options.conf_file); config_file = lib::FileUtil::GetAbsolutePath(work_root, config_file); @@ -179,33 +179,33 @@ FusionCameraDetectionComponent::~FusionCameraDetectionComponent() {} bool FusionCameraDetectionComponent::Init() { writer_ = node_->CreateWriter("/perception/obstacles"); - if (InitConfig() != cybertron::SUCC) { + if (InitConfig() != cyber::SUCC) { AERROR << "InitConfig() failed."; - return cybertron::FAIL; + return cyber::FAIL; } - if (InitSensorInfo() != cybertron::SUCC) { + if (InitSensorInfo() != cyber::SUCC) { AERROR << "InitSensorInfo() failed."; - return cybertron::FAIL; + return cyber::FAIL; } - if (InitAlgorithmPlugin() != cybertron::SUCC) { + if (InitAlgorithmPlugin() != cyber::SUCC) { AERROR << "InitAlgorithmPlugin() failed."; - return cybertron::FAIL; + return cyber::FAIL; } - if (InitCameraFrames() != cybertron::SUCC) { + if (InitCameraFrames() != cyber::SUCC) { AERROR << "InitCameraFrames() failed."; - return cybertron::FAIL; + return cyber::FAIL; } - if (InitProjectMatrix() != cybertron::SUCC) { + if (InitProjectMatrix() != cyber::SUCC) { AERROR << "InitProjectMatrix() failed."; - return cybertron::FAIL; + return cyber::FAIL; } - if (InitCameraListeners() != cybertron::SUCC) { + if (InitCameraListeners() != cyber::SUCC) { AERROR << "InitCameraListeners() failed."; - return cybertron::FAIL; + return cyber::FAIL; } SetCameraHeightAndPitch(); - return cybertron::SUCC; + return cyber::SUCC; } void FusionCameraDetectionComponent::OnReceiveImage( @@ -246,10 +246,10 @@ void FusionCameraDetectionComponent::OnReceiveImage( SensorFrameMessage); if (InternalProc(message, camera_name, &error_code, prefused_message.get(), - out_message.get()) != cybertron::SUCC) { + out_message.get()) != cyber::SUCC) { AERROR << "InternalProc failed, error_code: " << error_code; if (MakeProtobufMsg(msg_timestamp, seq_num_, std::vector(), - error_code, out_message.get()) != cybertron::SUCC) { + error_code, out_message.get()) != cyber::SUCC) { AERROR << "MakeProtobufMsg failed"; return; } @@ -277,7 +277,7 @@ void FusionCameraDetectionComponent::OnReceiveImage( } int FusionCameraDetectionComponent::InitConfig() { - // the macro READ_CONF would return cybertron::FAIL if config not exists + // the macro READ_CONF would return cyber::FAIL if config not exists apollo::perception::onboard::FusionCameraDetection fusion_camera_detection_param; if (!GetProtoConfig(&fusion_camera_detection_param)) { @@ -290,7 +290,7 @@ int FusionCameraDetectionComponent::InitConfig() { boost::algorithm::is_any_of(",")); if (camera_names_.size() != 2) { AERROR << "Now FusionCameraDetectionComponent only support 2 cameras"; - return cybertron::FAIL; + return cyber::FAIL; } std::string input_camera_channel_names_str = @@ -301,7 +301,7 @@ int FusionCameraDetectionComponent::InitConfig() { if (input_camera_channel_names_.size() != camera_names_.size()) { AERROR << "wrong input_camera_channel_names_.size(): " << input_camera_channel_names_.size(); - return cybertron::FAIL; + return cyber::FAIL; } camera_perception_init_options_.root_dir = @@ -310,7 +310,7 @@ int FusionCameraDetectionComponent::InitConfig() { fusion_camera_detection_param.camera_obstacle_perception_conf_file(); camera_perception_init_options_.lane_calibration_working_sensor_name = fusion_camera_detection_param.lane_calibration_working_sensor_name(); - camera_perception_init_options_.use_cybertron_work_root = true; + camera_perception_init_options_.use_cyber_work_root = true; frame_capacity_ = fusion_camera_detection_param.frame_capacity(); image_channel_num_ = fusion_camera_detection_param.image_channel_num(); enable_undistortion_ = fusion_camera_detection_param.enable_undistortion(); @@ -356,13 +356,13 @@ int FusionCameraDetectionComponent::InitConfig() { output_final_obstacles_ % prefused_channel_name_); AINFO << config_info_str; - return cybertron::SUCC; + return cyber::SUCC; } int FusionCameraDetectionComponent::InitSensorInfo() { if (camera_names_.size() != 2) { AERROR << "invalid camera_names_.size(): " << camera_names_.size(); - return cybertron::FAIL; + return cyber::FAIL; } common::SensorManager *sensor_manager = @@ -370,13 +370,13 @@ int FusionCameraDetectionComponent::InitSensorInfo() { for (size_t i = 0; i < camera_names_.size(); ++i) { if (!sensor_manager->IsSensorExist(camera_names_[i])) { AERROR << ("sensor_name: " + camera_names_[i] + " not exists."); - return cybertron::FAIL; + return cyber::FAIL; } base::SensorInfo sensor_info; if (!(sensor_manager->GetSensorInfo(camera_names_[i], &sensor_info))) { AERROR << "Failed to get sensor info, sensor name: " << camera_names_[i]; - return cybertron::FAIL; + return cyber::FAIL; } sensor_info_map_[camera_names_[i]] = sensor_info; @@ -407,28 +407,28 @@ int FusionCameraDetectionComponent::InitSensorInfo() { image_height_ % image_channel_num_); AINFO << sensor_info_str; - return cybertron::SUCC; + return cyber::SUCC; } int FusionCameraDetectionComponent::InitAlgorithmPlugin() { camera_obstacle_pipeline_.reset(new camera::ObstacleCameraPerception); if (!camera_obstacle_pipeline_->Init(camera_perception_init_options_)) { AERROR << "camera_obstacle_pipeline_->Init() failed"; - return cybertron::FAIL; + return cyber::FAIL; } - return cybertron::SUCC; + return cyber::SUCC; } int FusionCameraDetectionComponent::InitCameraFrames() { if (camera_names_.size() != 2) { AERROR << "invalid camera_names_.size(): " << camera_names_.size(); - return cybertron::FAIL; + return cyber::FAIL; } // fixed size camera_frames_.resize(frame_capacity_); if (camera_frames_.size() == 0) { AERROR << "frame_capacity_ must > 0"; - return cybertron::FAIL; + return cyber::FAIL; } // init data_providers for each camera @@ -440,7 +440,7 @@ int FusionCameraDetectionComponent::InitCameraFrames() { data_provider_init_options.sensor_name = camera_name; int gpu_id = GetGpuId(camera_perception_init_options_); if (gpu_id == -1) { - return cybertron::FAIL; + return cyber::FAIL; } data_provider_init_options.device_id = gpu_id; AINFO << "data_provider_init_options.device_id: " @@ -482,14 +482,14 @@ int FusionCameraDetectionComponent::InitCameraFrames() { frame.track_feature_blob.reset(new base::Blob()); frame.lane_detected_blob.reset(new base::Blob()); } - return cybertron::SUCC; + return cyber::SUCC; } int FusionCameraDetectionComponent::InitProjectMatrix() { if (!GetProjectMatrix(camera_names_, extrinsic_map_, intrinsic_map_, &project_matrix_, &pitch_diff_)) { AERROR << "GetProjectMatrix failed"; - return cybertron::FAIL; + return cyber::FAIL; } AINFO << "project_matrix_: " << project_matrix_; AINFO << "pitch_diff_:" << pitch_diff_; @@ -497,7 +497,7 @@ int FusionCameraDetectionComponent::InitProjectMatrix() { name_camera_pitch_angle_diff_map_[camera_names_[1]] = static_cast(pitch_diff_); - return cybertron::SUCC; + return cyber::SUCC; } int FusionCameraDetectionComponent::InitCameraListeners() { @@ -513,7 +513,7 @@ int FusionCameraDetectionComponent::InitCameraListeners() { std::placeholders::_1, camera_name); auto camera_reader = node_->CreateReader(channel_name, camera_callback); } - return cybertron::SUCC; + return cyber::SUCC; } void FusionCameraDetectionComponent::SetCameraHeightAndPitch() { @@ -543,14 +543,14 @@ int FusionCameraDetectionComponent::InternalProc( // Get sensor to world pose from TF Eigen::Affine3d camera2world_trans; if (camera2world_trans_wrapper_map_[camera_name]->GetSensor2worldTrans( - msg_timestamp, &camera2world_trans) != cybertron::SUCC) { + msg_timestamp, &camera2world_trans) != cyber::SUCC) { std::string err_str = "failed to get camera to world pose, ts: " + std::to_string(msg_timestamp) + " camera_name: " + camera_name; AERROR << err_str; *error_code = apollo::common::ErrorCode::PERCEPTION_ERROR_TF; prefused_message->error_code_ = *error_code; - return cybertron::FAIL; + return cyber::FAIL; } prefused_message->frame_->sensor2world_pose = camera2world_trans; @@ -583,7 +583,7 @@ int FusionCameraDetectionComponent::InternalProc( << " msg_timestamp: " << std::to_string(msg_timestamp); *error_code = apollo::common::ErrorCode::PERCEPTION_ERROR_PROCESS; prefused_message->error_code_ = *error_code; - return cybertron::FAIL; + return cyber::FAIL; } AINFO << "##" << camera_name << ": pitch " << camera_frame.calibration_service->QueryPitchAngle() @@ -602,12 +602,12 @@ int FusionCameraDetectionComponent::InternalProc( // process success, make pb msg if (output_final_obstacles_ && MakeProtobufMsg(msg_timestamp, seq_num_, camera_frame.tracked_objects, - *error_code, out_message) != cybertron::SUCC) { + *error_code, out_message) != cyber::SUCC) { AERROR << "MakeProtobufMsg failed" << " ts: " << std::to_string(msg_timestamp); *error_code = apollo::common::ErrorCode::PERCEPTION_ERROR_UNKNOWN; prefused_message->error_code_ = *error_code; - return cybertron::FAIL; + return cyber::FAIL; } *error_code = apollo::common::ErrorCode::PERCEPTION_ERROR_NONE; prefused_message->error_code_ = *error_code; @@ -639,7 +639,7 @@ int FusionCameraDetectionComponent::InternalProc( // Send(camera_perception_viz_message_channel_name_, viz_msg); } - return cybertron::SUCC; + return cyber::SUCC; } int FusionCameraDetectionComponent::MakeProtobufMsg( @@ -647,7 +647,7 @@ int FusionCameraDetectionComponent::MakeProtobufMsg( const std::vector &objects, const apollo::common::ErrorCode error_code, apollo::perception::PerceptionObstacles *obstacles) { - double publish_time = apollo::cybertron::Time::Now().ToSecond(); + double publish_time = apollo::cyber::Time::Now().ToSecond(); apollo::common::Header *header = obstacles->mutable_header(); header->set_timestamp_sec(publish_time); header->set_module_name("perception_camera"); @@ -662,19 +662,19 @@ int FusionCameraDetectionComponent::MakeProtobufMsg( for (const auto &obj : objects) { apollo::perception::PerceptionObstacle *obstacle = obstacles->add_perception_obstacle(); - if (ConvertObjectToPb(obj, obstacle) != cybertron::SUCC) { + if (ConvertObjectToPb(obj, obstacle) != cyber::SUCC) { AERROR << "ConvertObjectToPb failed, Object:" << obj->ToString(); - return cybertron::FAIL; + return cyber::FAIL; } } - return cybertron::SUCC; + return cyber::SUCC; } int FusionCameraDetectionComponent::ConvertObjectToPb( const base::ObjectPtr &object_ptr, apollo::perception::PerceptionObstacle *pb_msg) { if (!object_ptr || !pb_msg) { - return cybertron::FAIL; + return cyber::FAIL; } pb_msg->set_id(object_ptr->track_id); @@ -746,7 +746,7 @@ int FusionCameraDetectionComponent::ConvertObjectToPb( light_status->set_right_turn_switch_on(car_light.right_turn_switch_on); } - return cybertron::SUCC; + return cyber::SUCC; } } // namespace onboard diff --git a/modules/perception/onboard/component/fusion_camera_detection_component.h b/modules/perception/onboard/component/fusion_camera_detection_component.h index 84e447499a2..ddd095b0369 100644 --- a/modules/perception/onboard/component/fusion_camera_detection_component.h +++ b/modules/perception/onboard/component/fusion_camera_detection_component.h @@ -24,7 +24,7 @@ #include #include -#include "cybertron/component/component.h" +#include "cyber/component/component.h" #include "modules/drivers/proto/sensor_image.pb.h" #include "modules/perception/base/object.h" #include "modules/perception/base/object_types.h" @@ -43,7 +43,7 @@ namespace perception { namespace onboard { class FusionCameraDetectionComponent : - public apollo::cybertron::Component<> { + public apollo::cyber::Component<> { public: FusionCameraDetectionComponent() : seq_num_(0) {} ~FusionCameraDetectionComponent(); @@ -87,7 +87,7 @@ class FusionCameraDetectionComponent : std::mutex mutex_; uint32_t seq_num_; - std::vector > camera_listener_nodes_; + std::vector > camera_listener_nodes_; std::vector camera_names_; // camera sensor names std::vector input_camera_channel_names_; @@ -157,14 +157,14 @@ class FusionCameraDetectionComponent : double last_timestamp_ = 0.0; double ts_diff_ = 1.0; - std::shared_ptr> writer_; -// std::shared_ptr> +// std::shared_ptr> // sensorframe_writer_; }; -CYBERTRON_REGISTER_COMPONENT(FusionCameraDetectionComponent); +CYBER_REGISTER_COMPONENT(FusionCameraDetectionComponent); } // namespace onboard } // namespace perception diff --git a/modules/perception/onboard/component/fusion_component.h b/modules/perception/onboard/component/fusion_component.h index 31c2915a516..d6b27f5e825 100644 --- a/modules/perception/onboard/component/fusion_component.h +++ b/modules/perception/onboard/component/fusion_component.h @@ -20,7 +20,7 @@ #include #include -#include "cybertron/component/component.h" +#include "cyber/component/component.h" #include "modules/perception/base/object.h" #include "modules/perception/fusion/app/obstacle_multi_sensor_fusion.h" #include "modules/perception/fusion/lib/interface/base_fusion_system.h" @@ -31,7 +31,7 @@ namespace apollo { namespace perception { namespace onboard { -class FusionComponent : public cybertron::Component { +class FusionComponent : public cyber::Component { public: FusionComponent() = default; ~FusionComponent() = default; @@ -49,11 +49,11 @@ class FusionComponent : public cybertron::Component { static uint32_t s_seq_num_; std::unique_ptr fusion_; map::HDMapInput* hdmap_input_ = nullptr; - std::shared_ptr> writer_; - std::shared_ptr> inner_writer_; + std::shared_ptr> writer_; + std::shared_ptr> inner_writer_; }; -CYBERTRON_REGISTER_COMPONENT(FusionComponent); +CYBER_REGISTER_COMPONENT(FusionComponent); } // namespace onboard } // namespace perception diff --git a/modules/perception/onboard/component/lidar_inner_component_messages.h b/modules/perception/onboard/component/lidar_inner_component_messages.h index c179cdc3b3f..cc483c85aee 100644 --- a/modules/perception/onboard/component/lidar_inner_component_messages.h +++ b/modules/perception/onboard/component/lidar_inner_component_messages.h @@ -18,7 +18,7 @@ #include #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/perception/lidar/common/lidar_frame.h" #include "modules/perception/onboard/inner_component_messages/inner_component_messages.h" #include "modules/perception/proto/perception_obstacle.pb.h" @@ -27,7 +27,7 @@ namespace apollo { namespace perception { namespace onboard { -class LidarFrameMessage : public apollo::cybertron::message::IntraMessage { +class LidarFrameMessage : public apollo::cyber::message::IntraMessage { public: LidarFrameMessage() : lidar_frame_(nullptr) { type_name_ = "LidarFrameMessage"; diff --git a/modules/perception/onboard/component/lidar_output_component.h b/modules/perception/onboard/component/lidar_output_component.h index 1616f6a4844..0fa4273aca1 100644 --- a/modules/perception/onboard/component/lidar_output_component.h +++ b/modules/perception/onboard/component/lidar_output_component.h @@ -17,14 +17,14 @@ #include -#include "cybertron/component/component.h" +#include "cyber/component/component.h" #include "modules/perception/onboard/inner_component_messages/inner_component_messages.h" namespace apollo { namespace perception { namespace onboard { -class LidarOutputComponent : public cybertron::Component { +class LidarOutputComponent : public cyber::Component { public: LidarOutputComponent() = default; ~LidarOutputComponent() = default; @@ -33,10 +33,10 @@ class LidarOutputComponent : public cybertron::Component { bool Proc(const std::shared_ptr& message) override; private: - std::shared_ptr> writer_; + std::shared_ptr> writer_; }; // class LidarOutputComponent -CYBERTRON_REGISTER_COMPONENT(LidarOutputComponent); +CYBER_REGISTER_COMPONENT(LidarOutputComponent); } // namespace onboard } // namespace perception diff --git a/modules/perception/onboard/component/radar_detection_component.h b/modules/perception/onboard/component/radar_detection_component.h index a6603295807..9e12ce0a6d9 100644 --- a/modules/perception/onboard/component/radar_detection_component.h +++ b/modules/perception/onboard/component/radar_detection_component.h @@ -19,7 +19,7 @@ #include #include -#include "cybertron/component/component.h" +#include "cyber/component/component.h" #include "modules/localization/proto/localization.pb.h" #include "modules/perception/base/sensor_meta.h" #include "modules/perception/lib/utils/time_util.h" @@ -35,13 +35,13 @@ namespace apollo { namespace perception { namespace onboard { -using apollo::cybertron::FAIL; -using apollo::cybertron::SUCC; +using apollo::cyber::FAIL; +using apollo::cyber::SUCC; using apollo::drivers::ContiRadar; using apollo::localization::LocalizationEstimate; using apollo::perception::onboard::RadarComponentConfig; -class RadarDetectionComponent : public cybertron::Component { +class RadarDetectionComponent : public cyber::Component { public: RadarDetectionComponent() : seq_num_(0), @@ -78,10 +78,10 @@ class RadarDetectionComponent : public cybertron::Component { std::shared_ptr radar_preprocessor_; std::shared_ptr radar_perception_; MsgBuffer localization_subscriber_; - std::shared_ptr> writer_; + std::shared_ptr> writer_; }; -CYBERTRON_REGISTER_COMPONENT(RadarDetectionComponent); +CYBER_REGISTER_COMPONENT(RadarDetectionComponent); } // namespace onboard } // namespace perception diff --git a/modules/perception/onboard/component/recognition_component.h b/modules/perception/onboard/component/recognition_component.h index 3494d4fdaaa..c7a4ecd8811 100644 --- a/modules/perception/onboard/component/recognition_component.h +++ b/modules/perception/onboard/component/recognition_component.h @@ -18,7 +18,7 @@ #include #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/perception/base/sensor_meta.h" #include "modules/perception/lidar/app/lidar_obstacle_tracking.h" @@ -30,7 +30,7 @@ namespace apollo { namespace perception { namespace onboard { -class RecognitionComponent : public cybertron::Component { +class RecognitionComponent : public cyber::Component { public: RecognitionComponent() : tracker_(nullptr) {} ~RecognitionComponent() = default; @@ -46,10 +46,10 @@ class RecognitionComponent : public cybertron::Component { base::SensorInfo sensor_info_; std::string main_sensor_name_; std::string output_channel_name_; - std::shared_ptr> writer_; + std::shared_ptr> writer_; }; -CYBERTRON_REGISTER_COMPONENT(RecognitionComponent); +CYBER_REGISTER_COMPONENT(RecognitionComponent); } // namespace onboard } // namespace perception diff --git a/modules/perception/onboard/component/segmentation_component.h b/modules/perception/onboard/component/segmentation_component.h index e243f1aeb73..14ce3270edd 100644 --- a/modules/perception/onboard/component/segmentation_component.h +++ b/modules/perception/onboard/component/segmentation_component.h @@ -18,7 +18,7 @@ #include #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/drivers/proto/pointcloud.pb.h" #include "modules/perception/lidar/app/lidar_obstacle_segmentation.h" #include "modules/perception/lidar/common/lidar_frame.h" @@ -31,7 +31,7 @@ namespace apollo { namespace perception { namespace onboard { -class SegmentationComponent : public cybertron::Component { +class SegmentationComponent : public cyber::Component { public: SegmentationComponent() : segmentor_(nullptr) {} @@ -57,10 +57,10 @@ class SegmentationComponent : public cybertron::Component { base::SensorInfo sensor_info_; TransformWrapper lidar2world_trans_; std::unique_ptr segmentor_; - std::shared_ptr> writer_; + std::shared_ptr> writer_; }; -CYBERTRON_REGISTER_COMPONENT(SegmentationComponent); +CYBER_REGISTER_COMPONENT(SegmentationComponent); } // namespace onboard } // namespace perception diff --git a/modules/perception/onboard/component/trafficlights_perception_component.cc b/modules/perception/onboard/component/trafficlights_perception_component.cc index 39bca9d1d3e..c68f67053b6 100644 --- a/modules/perception/onboard/component/trafficlights_perception_component.cc +++ b/modules/perception/onboard/component/trafficlights_perception_component.cc @@ -27,8 +27,8 @@ #include #include -#include "cybertron/common/log.h" -#include "cybertron/time/time.h" +#include "cyber/common/log.h" +#include "cyber/time/time.h" #include "modules/common/math/math_utils.h" #include "modules/common/time/time_util.h" #include "modules/common/util/file.h" @@ -50,7 +50,7 @@ static int GetGpuId( const apollo::perception::camera::CameraPerceptionInitOptions& options) { apollo::perception::camera::app::TrafficLightParam trafficlight_param; std::string work_root = ""; - apollo::perception::camera::GetCybertronWorkRoot(&work_root); + apollo::perception::camera::GetCyberWorkRoot(&work_root); std::string config_file = lib::FileUtil::GetAbsolutePath(options.root_dir, options.conf_file); @@ -76,28 +76,28 @@ bool TrafficLightsPerceptionComponent::Init() { writer_ = node_->CreateWriter( "/perception/traffic_light"); - if (InitConfig() != cybertron::SUCC) { + if (InitConfig() != cyber::SUCC) { AERROR << "TrafficLightsPerceptionComponent InitConfig failed."; - return cybertron::FAIL; + return cyber::FAIL; } - if (InitAlgorithmPlugin() != cybertron::SUCC) { + if (InitAlgorithmPlugin() != cyber::SUCC) { AERROR << "TrafficLightsPerceptionComponent InitAlgorithmPlugin failed."; - return cybertron::FAIL; + return cyber::FAIL; } - if (InitCameraListeners() != cybertron::SUCC) { + if (InitCameraListeners() != cyber::SUCC) { AERROR << "TrafficLightsPerceptionComponent InitCameraListeners failed."; - return cybertron::FAIL; + return cyber::FAIL; } - if (InitCameraFrame() != cybertron::SUCC) { + if (InitCameraFrame() != cyber::SUCC) { AERROR << "TrafficLightsPerceptionComponent InitCameraFrame failed."; - return cybertron::FAIL; + return cyber::FAIL; } AINFO << "TrafficLight Preproc Init Success"; - return cybertron::SUCC; + return cyber::SUCC; } int TrafficLightsPerceptionComponent::InitConfig() { @@ -155,7 +155,7 @@ int TrafficLightsPerceptionComponent::InitConfig() { traffic_light_output_channel_name_ = traffic_light_param.traffic_light_output_channel_name(); - return cybertron::SUCC; + return cyber::SUCC; } int TrafficLightsPerceptionComponent::InitAlgorithmPlugin() { @@ -163,30 +163,30 @@ int TrafficLightsPerceptionComponent::InitAlgorithmPlugin() { preprocessor_.reset(new camera::TLPreprocessor); if (!preprocessor_) { AERROR << "TrafficLightsPerceptionComponent new preprocessor failed"; - return cybertron::FAIL; + return cyber::FAIL; } preprocessor_init_options_.camera_names = camera_names_; if (!preprocessor_->Init(preprocessor_init_options_)) { AERROR << "TrafficLightsPerceptionComponent init preprocessor failed"; - return cybertron::FAIL; + return cyber::FAIL; } const auto camera_names_by_descending_focal_len = preprocessor_->GetCameraNamesByDescendingFocalLen(); if (camera_names_by_descending_focal_len.empty()) { AERROR << "empty camera_names in preprocessor"; - return cybertron::FAIL; + return cyber::FAIL; } if (camera_names_.size() != input_camera_channel_names_.size() || camera_names_.size() == 0) { AERROR << "invalid camera_names config"; - return cybertron::FAIL; + return cyber::FAIL; } SensorManager* sensor_manager = lib::Singleton::get_instance(); for (size_t i = 0; i < camera_names_.size(); ++i) { if (!sensor_manager->IsSensorExist(camera_names_[i])) { AERROR << ("sensor_name: " + camera_names_[i] + " not exists."); - return cybertron::FAIL; + return cyber::FAIL; } // init transform wrappers @@ -207,22 +207,22 @@ int TrafficLightsPerceptionComponent::InitAlgorithmPlugin() { hd_map_ = lib::Singleton::get_instance(); if (hd_map_ == nullptr) { AERROR << "PreprocessComponent get hdmap failed."; - return cybertron::FAIL; + return cyber::FAIL; } if (!hd_map_->Init()) { AERROR << "PreprocessComponent init hd-map failed."; - return cybertron::FAIL; + return cyber::FAIL; } - camera_perception_init_options_.use_cybertron_work_root = true; + camera_perception_init_options_.use_cyber_work_root = true; traffic_light_pipeline_.reset(new camera::TrafficLightCameraPerception); if (!traffic_light_pipeline_->Init(camera_perception_init_options_)) { AERROR << "camera_obstacle_pipeline_->Init() failed"; - return cybertron::FAIL; + return cyber::FAIL; } - return cybertron::SUCC; + return cyber::SUCC; } int TrafficLightsPerceptionComponent::InitCameraListeners() { @@ -242,7 +242,7 @@ int TrafficLightsPerceptionComponent::InitCameraListeners() { last_sub_camera_image_ts_[camera_name] = 0.0; } - return cybertron::SUCC; + return cyber::SUCC; } int TrafficLightsPerceptionComponent::InitCameraFrame() { @@ -250,7 +250,7 @@ int TrafficLightsPerceptionComponent::InitCameraFrame() { data_provider_init_options_.image_width = image_width_; int gpu_id = GetGpuId(camera_perception_init_options_); if (gpu_id == -1) { - return cybertron::FAIL; + return cyber::FAIL; } data_provider_init_options_.device_id = gpu_id; AINFO << "trafficlights data_provider_init_options_.device_id: " @@ -265,12 +265,12 @@ int TrafficLightsPerceptionComponent::InitCameraFrame() { if (!data_provider->Init(data_provider_init_options_)) { AERROR << "trafficlights init data_provider failed. " << " camera_name: " << camera_name; - return cybertron::FAIL; + return cyber::FAIL; } data_providers_map_[camera_name] = data_provider; } - return cybertron::SUCC; + return cyber::SUCC; } void TrafficLightsPerceptionComponent::OnReceiveImage( @@ -642,13 +642,13 @@ bool TrafficLightsPerceptionComponent::GetCarPose( } int state = 0; - int ret = cybertron::FAIL; + int ret = cyber::FAIL; Eigen::Affine3d affine3d_trans; for (const auto &camera_name : camera_names_) { const auto trans_wrapper = camera2world_trans_wrapper_map_[camera_name]; ret = trans_wrapper->GetSensor2worldTrans(timestamp, &affine3d_trans); pose_matrix = affine3d_trans.matrix(); - if (ret != cybertron::SUCC) { + if (ret != cyber::SUCC) { pose->ClearCameraPose(camera_name); AERROR << "get pose from tf failed, camera_name: " << camera_name; @@ -666,7 +666,7 @@ bool TrafficLightsPerceptionComponent::GetPoseFromTF( const std::string& child_frame_id, Eigen::Matrix4d* pose_matrix) { PERCEPTION_PERF_FUNCTION(); - apollo::cybertron::Time query_time(timestamp); + apollo::cyber::Time query_time(timestamp); std::string err_string; if (!tf2_buffer_->canTransform(frame_id, child_frame_id, query_time, tf2_timeout_second_, &err_string)) { @@ -713,7 +713,7 @@ bool TrafficLightsPerceptionComponent::TransformOutputMessage( const auto &lights = frame->traffic_lights; auto *header = (*out_msg)->mutable_header(); - double publish_time = apollo::cybertron::Time::Now().ToSecond(); + double publish_time = apollo::cyber::Time::Now().ToSecond(); header->set_timestamp_sec(publish_time); // message publishing time AINFO << "set header time sec:" << std::to_string(frame->timestamp); diff --git a/modules/perception/onboard/component/trafficlights_perception_component.h b/modules/perception/onboard/component/trafficlights_perception_component.h index af635104444..69f3d6941cb 100644 --- a/modules/perception/onboard/component/trafficlights_perception_component.h +++ b/modules/perception/onboard/component/trafficlights_perception_component.h @@ -24,7 +24,7 @@ #include #include -#include "cybertron/component/component.h" +#include "cyber/component/component.h" #include "modules/drivers/proto/sensor_image.pb.h" #include "modules/map/proto/map_geometry.pb.h" #include "modules/map/proto/map_signal.pb.h" @@ -43,7 +43,7 @@ namespace perception { namespace onboard { class TrafficLightsPerceptionComponent : - public apollo::cybertron::Component<> { + public apollo::cyber::Component<> { public: TrafficLightsPerceptionComponent() = default; ~TrafficLightsPerceptionComponent() = default; @@ -126,7 +126,7 @@ class TrafficLightsPerceptionComponent : // camera_name -> image_border_size std::map image_border_sizes_; - std::vector > camera_listener_nodes_; + std::vector > camera_listener_nodes_; double last_sub_tf_ts_ = 0.0; @@ -178,11 +178,11 @@ class TrafficLightsPerceptionComponent : std::string simulation_channel_name_; std::string traffic_light_output_channel_name_; - std::shared_ptr> writer_; }; -CYBERTRON_REGISTER_COMPONENT(TrafficLightsPerceptionComponent); +CYBER_REGISTER_COMPONENT(TrafficLightsPerceptionComponent); } // namespace onboard } // namespace perception diff --git a/modules/perception/onboard/inner_component_messages/inner_component_messages.h b/modules/perception/onboard/inner_component_messages/inner_component_messages.h index 88c94144534..56c1d35c176 100644 --- a/modules/perception/onboard/inner_component_messages/inner_component_messages.h +++ b/modules/perception/onboard/inner_component_messages/inner_component_messages.h @@ -20,7 +20,7 @@ #include #include -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "modules/perception/base/frame.h" #include "modules/perception/base/hdmap_struct.h" #include "modules/perception/base/impending_collision_edge.h" @@ -49,7 +49,7 @@ class Descriptor { std::string full_name() { return "name"; } }; -class SensorFrameMessage : public apollo::cybertron::message::IntraMessage { +class SensorFrameMessage : public apollo::cyber::message::IntraMessage { public: SensorFrameMessage() { type_name_ = "SensorFrameMessage"; } ~SensorFrameMessage() = default; diff --git a/modules/perception/onboard/msg_buffer/BUILD b/modules/perception/onboard/msg_buffer/BUILD index 3e371ba1ad6..ee02a3bc03f 100644 --- a/modules/perception/onboard/msg_buffer/BUILD +++ b/modules/perception/onboard/msg_buffer/BUILD @@ -14,7 +14,7 @@ cc_library( "msg_buffer.h", ], deps = [ - "//cybertron", + "//cyber", ], ) diff --git a/modules/perception/onboard/msg_buffer/msg_buffer.h b/modules/perception/onboard/msg_buffer/msg_buffer.h index 0cfa7390e41..e4645d87e17 100644 --- a/modules/perception/onboard/msg_buffer/msg_buffer.h +++ b/modules/perception/onboard/msg_buffer/msg_buffer.h @@ -22,7 +22,7 @@ #include #include "boost/circular_buffer.hpp" -#include "cybertron/cybertron.h" +#include "cyber/cyber.h" #include "gflags/gflags.h" namespace apollo { @@ -60,8 +60,8 @@ class MsgBuffer { private: std::string node_name_; - std::unique_ptr node_; - std::shared_ptr> msg_subscriber_; + std::unique_ptr node_; + std::shared_ptr> msg_subscriber_; std::mutex buffer_mutex_; bool init_ = false; @@ -76,7 +76,7 @@ void MsgBuffer::Init(const std::string& channel, const std::string& name) { } else { node_name_ = name + "_subscriber"; } - node_.reset(apollo::cybertron::CreateNode(node_name_).release()); + node_.reset(apollo::cyber::CreateNode(node_name_).release()); std::function register_call = std::bind(&MsgBuffer::MsgCallback, this, std::placeholders::_1); @@ -99,23 +99,23 @@ int MsgBuffer::LookupNearest(double timestamp, ConstPtr* msg) { std::lock_guard lock(buffer_mutex_); if (!init_) { AERROR << "msg buffer is uninitialized."; - return cybertron::FAIL; + return cyber::FAIL; } if (buffer_queue_.empty()) { AERROR << "msg buffer is empty."; - return cybertron::FAIL; + return cyber::FAIL; } if (buffer_queue_.front().first - FLAGS_obs_buffer_match_precision > timestamp) { AERROR << "Your timestamp (" << timestamp << ") is earlier than the oldest " << "timestamp (" << buffer_queue_.front().first << ")."; - return cybertron::FAIL; + return cyber::FAIL; } if (buffer_queue_.back().first + FLAGS_obs_buffer_match_precision < timestamp) { AERROR << "Your timestamp (" << timestamp << ") is newer than the latest " << "timestamp (" << buffer_queue_.back().first << ")."; - return cybertron::FAIL; + return cyber::FAIL; } // loop to find nearest @@ -130,7 +130,7 @@ int MsgBuffer::LookupNearest(double timestamp, ConstPtr* msg) { } *msg = buffer_queue_[idx + 1].second; - return cybertron::SUCC; + return cyber::SUCC; } template @@ -138,14 +138,14 @@ int MsgBuffer::LookupLatest(ConstPtr* msg) { std::lock_guard lock(buffer_mutex_); if (!init_) { AERROR << "msg buffer is uninitialized."; - return cybertron::FAIL; + return cyber::FAIL; } if (buffer_queue_.empty()) { AERROR << "msg buffer is empty."; - return cybertron::FAIL; + return cyber::FAIL; } *msg = buffer_queue_.back().second; - return cybertron::SUCC; + return cyber::SUCC; } template @@ -154,23 +154,23 @@ int MsgBuffer::LookupPeriod(const double timestamp, const double period, std::lock_guard lock(buffer_mutex_); if (!init_) { AERROR << "msg buffer is uninitialized."; - return cybertron::FAIL; + return cyber::FAIL; } if (buffer_queue_.empty()) { AERROR << "msg buffer is empty."; - return cybertron::FAIL; + return cyber::FAIL; } if (buffer_queue_.front().first - FLAGS_obs_buffer_match_precision > timestamp) { AERROR << "Your timestamp (" << timestamp << ") is earlier than the oldest " << "timestamp (" << buffer_queue_.front().first << ")."; - return cybertron::FAIL; + return cyber::FAIL; } if (buffer_queue_.back().first + FLAGS_obs_buffer_match_precision < timestamp) { AERROR << "Your timestamp (" << timestamp << ") is newer than the latest " << "timestamp (" << buffer_queue_.back().first << ")."; - return cybertron::FAIL; + return cyber::FAIL; } const double lower_timestamp = timestamp - period; @@ -188,7 +188,7 @@ int MsgBuffer::LookupPeriod(const double timestamp, const double period, } } - return cybertron::SUCC; + return cyber::SUCC; } } // namespace onboard diff --git a/modules/perception/onboard/msg_serializer/BUILD b/modules/perception/onboard/msg_serializer/BUILD index 57d86d8e370..8cbe21744ec 100644 --- a/modules/perception/onboard/msg_serializer/BUILD +++ b/modules/perception/onboard/msg_serializer/BUILD @@ -12,7 +12,7 @@ cc_library( ], deps = [ "@eigen", - "//cybertron", + "//cyber", "//modules/perception/base", "//modules/perception/lib/utils", "//modules/perception/onboard/common_flags", diff --git a/modules/perception/onboard/msg_serializer/msg_serializer.cc b/modules/perception/onboard/msg_serializer/msg_serializer.cc index 5b60d210281..fcf9a184968 100644 --- a/modules/perception/onboard/msg_serializer/msg_serializer.cc +++ b/modules/perception/onboard/msg_serializer/msg_serializer.cc @@ -17,7 +17,7 @@ #include -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/lib/utils/time_util.h" #include "modules/perception/onboard/common_flags/common_flags.h" @@ -31,7 +31,7 @@ bool MsgSerializer::SerializeMsg(double timestamp, int seq_num, const apollo::common::ErrorCode &error_code, PerceptionObstacles *obstacles) { // double publish_time = lib::TimeUtil::GetCurrentTime(); - double publish_time = cybertron::Time::Now().ToSecond(); + double publish_time = cyber::Time::Now().ToSecond(); ::apollo::common::Header *header = obstacles->mutable_header(); header->set_timestamp_sec(publish_time); header->set_module_name("perception_obstacle"); diff --git a/modules/perception/onboard/msg_serializer/msg_serializer.h b/modules/perception/onboard/msg_serializer/msg_serializer.h index c8f1b532e82..882a623ebee 100644 --- a/modules/perception/onboard/msg_serializer/msg_serializer.h +++ b/modules/perception/onboard/msg_serializer/msg_serializer.h @@ -17,7 +17,7 @@ #include -#include "cybertron/time/time.h" +#include "cyber/time/time.h" #include "modules/perception/base/object.h" #include "modules/perception/proto/perception_obstacle.pb.h" diff --git a/modules/perception/onboard/transform_wrapper/transform_wrapper.cc b/modules/perception/onboard/transform_wrapper/transform_wrapper.cc index 9394250a739..b74e6775675 100644 --- a/modules/perception/onboard/transform_wrapper/transform_wrapper.cc +++ b/modules/perception/onboard/transform_wrapper/transform_wrapper.cc @@ -15,7 +15,7 @@ *****************************************************************************/ #include "modules/perception/onboard/transform_wrapper/transform_wrapper.h" -#include "cybertron/common/log.h" +#include "cyber/common/log.h" #include "modules/perception/common/sensor_manager/sensor_manager.h" namespace apollo { @@ -29,7 +29,7 @@ DEFINE_string(obs_novatel2world_tf2_frame_id, "world", DEFINE_string(obs_novatel2world_tf2_child_frame_id, "novatel", "novatel to world child frame id"); DEFINE_double(obs_tf2_buff_size, 0.01, - "query Cybertron TF buffer size in second"); + "query Cyber TF buffer size in second"); DEFINE_double(obs_transform_cache_size, 1.0, "transform cache size in second"); DEFINE_double(obs_max_local_pose_extrapolation_latency, 0.15, "max local pose extrapolation period in second"); @@ -218,7 +218,7 @@ bool TransformWrapper::GetTrans(double timestamp, Eigen::Affine3d* trans, bool TransformWrapper::QueryTrans(double timestamp, StampedTransform* trans, const std::string& frame_id, const std::string& child_frame_id) { - cybertron::Time query_time(timestamp); + cyber::Time query_time(timestamp); std::string err_string; if (!tf2_buffer_->canTransform(frame_id, child_frame_id, query_time, FLAGS_obs_tf2_buff_size, &err_string)) { diff --git a/modules/perception/production/conf/perception/perception.flag b/modules/perception/production/conf/perception/perception.flag index b08847e3e05..5e80ad5b068 100644 --- a/modules/perception/production/conf/perception/perception.flag +++ b/modules/perception/production/conf/perception/perception.flag @@ -81,7 +81,7 @@ # default: --obs_novatel2world_tf2_child_frame_id=novatel -# query Cybertron TF buffer size in second. +# query Cyber TF buffer size in second. # type: double # default: 0.01 --obs_tf2_buff_size=0.01 diff --git a/modules/perception/production/dag/dag_streaming_perception_camera.dag b/modules/perception/production/dag/dag_streaming_perception_camera.dag index 3f8352b3fa6..097031ef8b3 100644 --- a/modules/perception/production/dag/dag_streaming_perception_camera.dag +++ b/modules/perception/production/dag/dag_streaming_perception_camera.dag @@ -1,5 +1,5 @@ module_config { - module_library : "lib/libperception_camera_cybertron.so" + module_library : "lib/libperception_camera_cyber.so" components { comname : "FusionCameraDetection" comclass : "FusionCameraDetectionComponent" diff --git a/modules/perception/production/dag/dag_streaming_perception_camera_viz.dag b/modules/perception/production/dag/dag_streaming_perception_camera_viz.dag index e291d06435e..7d15a25ba7e 100644 --- a/modules/perception/production/dag/dag_streaming_perception_camera_viz.dag +++ b/modules/perception/production/dag/dag_streaming_perception_camera_viz.dag @@ -1,5 +1,5 @@ module_config { - module_library : "lib/libperception_camera_cybertron_viz.so" + module_library : "lib/libperception_camera_cyber_viz.so" components { comname : "FusionCameraDetectionViz" comclass : "FusionCameraDetectionComponent" diff --git a/modules/perception/production/launch/perception.launch b/modules/perception/production/launch/perception.launch index 8193f65c161..a46a9cd931b 100644 --- a/modules/perception/production/launch/perception.launch +++ b/modules/perception/production/launch/perception.launch @@ -1,7 +1,7 @@ - - cybertron modules list config + + cyber modules list config 1.0.0 - - cybertron modules list config + + cyber modules list config 1.0.0 - - cybertron modules list config + + cyber modules list config 1.0.0 - - cybertron modules list config + + cyber modules list config 1.0.0 - - cybertron modules list config + + cyber modules list config 1.0.0