cyber/node/node.h

Defined in cyber/node/node.h

class apollo::cyber::Node

Node is the fundamental building block of Cyber RT. every module contains and communicates through the node. A module can have different types of communication by defining read/write and/or service/client in a node.

警告

Duplicate name is not allowed in topo objects, such as node, reader/writer, service/clinet in the topo.

Public Functions

const std::string &Name() const

Get node’s name.

警告

duplicate node name is not allowed in the topo.

template<typename MessageT>
auto CreateWriter(const proto::RoleAttributes &role_attr) -> std::shared_ptr<Writer<MessageT>>

Create a Writer with specific message type.

模板参数

MessageT – Message Type

参数

role_attr – is a protobuf message RoleAttributes, which includes the channel name and other info.

返回

std::shared_ptr<Writer<MessageT>> result Writer Object

template<typename MessageT>
auto CreateWriter(const std::string &channel_name) -> std::shared_ptr<Writer<MessageT>>

Create a Writer with specific message type.

模板参数

MessageT – Message Type

参数

channel_name – the channel name to be published.

返回

std::shared_ptr<Writer<MessageT>> result Writer Object

template<typename MessageT>
auto CreateReader(const std::string &channel_name, const CallbackFunc<MessageT> &reader_func = nullptr) -> std::shared_ptr<cyber::Reader<MessageT>>

Create a Reader with specific message type with channel name qos and other configs used will be default.

模板参数

MessageT – Message Type

参数
  • channel_name – the channel of the reader subscribed.

  • reader_func – invoked when message receive invoked when the message is received.

返回

std::shared_ptr<cyber::Reader<MessageT>> result Reader Object

template<typename MessageT>
auto CreateReader(const ReaderConfig &config, const CallbackFunc<MessageT> &reader_func = nullptr) -> std::shared_ptr<cyber::Reader<MessageT>>

Create a Reader with specific message type with reader config.

模板参数

MessageT – Message Type

参数
  • config – instance of ReaderConfig, include channel name, qos and pending queue size

  • reader_func – invoked when message receive

返回

std::shared_ptr<cyber::Reader<MessageT>> result Reader Object

template<typename MessageT>
auto CreateReader(const proto::RoleAttributes &role_attr, const CallbackFunc<MessageT> &reader_func = nullptr) -> std::shared_ptr<cyber::Reader<MessageT>>

Create a Reader object with RoleAttributes

模板参数

MessageT – Message Type

参数
  • role_attr – instance of RoleAttributes, includes channel name, qos, etc.

  • reader_func – invoked when message receive

返回

std::shared_ptr<cyber::Reader<MessageT>> result Reader Object

template<typename Request, typename Response>
auto CreateService(const std::string &service_name, const typename Service<Request, Response>::ServiceCallback &service_callback) -> std::shared_ptr<Service<Request, Response>>

Create a Service object with specific service_name

模板参数
  • Request – Message Type of the Request

  • Response – Message Type of the Response

参数
  • service_name – specific service name to a serve

  • service_callback – invoked when a service is called

返回

std::shared_ptr<Service<Request, Response>> result Service

template<typename Request, typename Response>
auto CreateClient(const std::string &service_name) -> std::shared_ptr<Client<Request, Response>>

Create a Client object to request Service with service_name

模板参数
  • Request – Message Type of the Request

  • Response – Message Type of the Response

参数

service_name – specific service name to a Service

返回

std::shared_ptr<Client<Request, Response>> result Client

void Observe()

Observe all readers’ data.

void ClearData()

clear all readers’ data

template<typename MessageT>
auto GetReader(const std::string &channel_name) -> std::shared_ptr<Reader<MessageT>>

Get the Reader object that subscribe channel_name

模板参数

MessageT – Message Type

参数

channel_name – channel name

返回

std::shared_ptr<Reader<MessageT>> result reader

cyber/node/reader_base.h

Defined in cyber/node/reader_base.h

class apollo::cyber::ReaderBase

Base Class for Reader Reader is identified by one apollo::cyber::proto::RoleAttribute, it contains the channel_name, channel_id that we subscribe, and host_name, process_id and node that we are located, and qos that describes our transportation quality.

Subclassed by apollo::cyber::Reader< MessageT >

Public Functions

virtual bool Init() = 0

Init the Reader object.

返回

true if init successfully

返回

false if init failed

virtual void Shutdown() = 0

Shutdown the Reader object.

virtual void ClearData() = 0

Clear local data.

virtual void Observe() = 0

Get stored data.

virtual bool Empty() const = 0

Query whether the Reader has data to be handled.

返回

true if data container is empty

返回

false if data container has data

virtual bool HasReceived() const = 0

Query whether we have received data since last clear.

返回

true if the reader has received data

返回

false if the reader has not received data

virtual double GetDelaySec() const = 0

Get time interval of since last receive message.

返回

double seconds delay

virtual uint32_t PendingQueueSize() const = 0

Get the value of pending queue size.

返回

uint32_t result value

inline virtual bool HasWriter()

Query is there any writer that publish the subscribed channel.

返回

true if there is at least one Writer publish the channel

返回

false if there is no Writer publish the channel

inline virtual void GetWriters(std::vector<proto::RoleAttributes> *writers)

Get all writers pushlish the channel we subscribes.

参数

writers – result RoleAttributes vector

inline const std::string &GetChannelName() const

Get Reader’s Channel name.

返回

const std::string& channel name

inline uint64_t ChannelId() const

Get Reader’s Channel id.

返回

uint64_t channel id

inline const proto::QosProfile &QosProfile() const

Get qos profile.

You can see qos description

返回

const proto::QosProfile& result qos

inline bool IsInit() const

Query whether the Reader is initialized.

返回

true if the Reader has been inited

返回

false if the Reader has not been inited

cyber/node/reader.h

Defined in cyber/node/reader.h

template<typename MessageT>
class apollo::cyber::Reader : public apollo::cyber::ReaderBase

Reader subscribes a channel, it has two main functions:

  1. You can pass a CallbackFunc to handle the message then it arrived

  2. You can Observe messages that Blocker cached. Reader automatically push the message to Blocker’s PublishQueue, and we can use Observe to fetch messages from PublishQueue to ObserveQueue. But, if you have set CallbackFunc, you can ignore this. One Reader uses one ChannelBuffer, the message we are handling is stored in ChannelBuffer Reader will Join the topology when init and Leave the topology when shutdown

    警告

    To save resource, ChannelBuffer has limited length, it’s passed through the pending_queue_size param. pending_queue_size is default set to 1, So, If you handle slower than writer sending, older messages that are not handled will be lost. You can increase pending_queue_size to resolve this problem.

Subclassed by apollo::cyber::blocker::IntraReader< MessageT >

Public Functions

explicit Reader(const proto::RoleAttributes &role_attr, const CallbackFunc<MessageT> &reader_func = nullptr, uint32_t pending_queue_size = DEFAULT_PENDING_QUEUE_SIZE)

Constructor a Reader object.

警告

the received messages is enqueue a queue,the queue’s depth is pending_queue_size

参数
  • role_attr – is a protobuf message RoleAttributes, which includes the channel name and other info.

  • reader_func – is the callback function, when the message is received.

  • pending_queue_size – is the max depth of message cache queue.

virtual bool Init() override

Init Reader.

返回

true if init successfully

返回

false if init failed

virtual void Shutdown() override

Shutdown Reader.

virtual void Observe() override

Get All data that Blocker stores.

virtual void ClearData() override

Clear Blocker’s data.

virtual bool HasReceived() const override

Query whether we have received data since last clear.

返回

true if the reader has received data

返回

false if the reader has not received data

virtual bool Empty() const override

Query whether the Reader has data to be handled.

返回

true if blocker is empty

返回

false if blocker has data

virtual double GetDelaySec() const override

Get time interval of since last receive message.

返回

double seconds delay

virtual uint32_t PendingQueueSize() const override

Get pending_queue_size configuration.

返回

uint32_t the value of pending queue size

virtual void Enqueue(const std::shared_ptr<MessageT> &msg)

Push msg to Blocker’s PublishQueue

参数

msg – message ptr to be pushed

virtual void SetHistoryDepth(const uint32_t &depth)

Set Blocker’s PublishQueue’s capacity to depth

参数

depth – the value you want to set

virtual uint32_t GetHistoryDepth() const

Get Blocker’s PublishQueue’s capacity.

返回

uint32_t depth of the history

virtual std::shared_ptr<MessageT> GetLatestObserved() const

Get the latest message we Observe

返回

std::shared_ptr<MessageT> the latest message

virtual std::shared_ptr<MessageT> GetOldestObserved() const

Get the oldest message we Observe

返回

std::shared_ptr<MessageT> the oldest message

inline virtual Iterator Begin() const

Get the begin iterator of ObserveQueue, used to traverse.

返回

Iterator begin iterator

inline virtual Iterator End() const

Get the end iterator of ObserveQueue, used to traverse.

返回

Iterator begin iterator

virtual bool HasWriter() override

Is there is at least one writer publish the channel that we subscribes?

返回

true if the channel has writer

返回

false if the channel has no writer

virtual void GetWriters(std::vector<proto::RoleAttributes> *writers) override

Get all writers pushlish the channel we subscribes.

参数

writers – result vector of RoleAttributes

cyber/node/writer_base.h

Defined in cyber/node/writer_base.h

class apollo::cyber::WriterBase

Base class for a Writer. A Writer is an object to send messages through a ‘Channel’.

警告

One Writer can only write one channel. But different writers can write through the same channel

Subclassed by apollo::cyber::Writer< MessageT >

Public Functions

inline explicit WriterBase(const proto::RoleAttributes &role_attr)

Construct a new Writer Base object.

参数

role_attr – role attributes for this Writer

virtual bool Init() = 0

Init the Writer.

返回

true if init success

返回

false if init failed

virtual void Shutdown() = 0

Shutdown the Writer.

inline virtual bool HasReader()

Is there any Reader that subscribes our Channel? You can publish message when this return true.

返回

true if the channel has reader

返回

false if the channel has no reader

inline virtual void GetReaders(std::vector<proto::RoleAttributes> *readers)

Get all Readers that subscriber our writing channel.

参数

readers – result vector of RoleAttributes

inline const std::string &GetChannelName() const

Get Writer’s Channel name.

返回

const std::string& const reference to the channel name

inline bool IsInit() const

Is Writer initialized?

返回

true if the Writer is inited

返回

false if the Write is not inited

cyber/node/writer.h

Defined in cyber/node/writer.h

template<typename MessageT>
class apollo::cyber::Writer : public apollo::cyber::WriterBase

Subclassed by apollo::cyber::blocker::IntraWriter< MessageT >

Public Functions

explicit Writer(const proto::RoleAttributes &role_attr)

Construct a new Writer object.

参数

role_attr – we use RoleAttributes to identify a Writer

virtual bool Init() override

Init the Writer.

返回

true if init successfully

返回

false if init failed

virtual void Shutdown() override

Shutdown the Writer.

virtual bool Write(const MessageT &msg)

Write a MessageT instance.

参数

msg – the message we want to write

返回

true if write successfully

返回

false if write failed

virtual bool Write(const std::shared_ptr<MessageT> &msg_ptr)

Write a shared ptr of MessageT.

参数

msg_ptr – the message shared ptr we want to write

返回

true if write successfully

返回

false if write failed

virtual bool HasReader() override

Is there any Reader that subscribes our Channel? You can publish message when this return true.

返回

true if the channel has reader

返回

false if the channel has no reader

virtual void GetReaders(std::vector<proto::RoleAttributes> *readers) override

Get all Readers that subscriber our writing channel.

参数

readers – vector result of RoleAttributes

cyber/node/node_channel_impl.h

Defined in cyber/node/node_channel_impl.h

struct apollo::cyber::ReaderConfig

Public Functions

inline ReaderConfig()

< configurations for a Reader

Public Members

uint32_t pending_queue_size

configuration for responding ChannelBuffer.

Older messages will dropped if you have no time to handle

class apollo::cyber::NodeChannelImpl

The implementation for Node to create Objects connected by Channels. e.g. Channel Reader and Writer.

Public Functions

inline explicit NodeChannelImpl(const std::string &node_name)

Construct a new Node Channel Impl object.

参数

node_name – node name

inline virtual ~NodeChannelImpl()

Destroy the Node Channel Impl object.

inline const std::string &NodeName() const

get name of this node

返回

const std::string& actual node name

cyber/node/node_service_impl.h

Defined in cyber/node/node_service_impl.h

class apollo::cyber::NodeServiceImpl

The implementation for Node to create Objects connected by Param. e.g. Param Server and Client.

Public Functions

inline explicit NodeServiceImpl(const std::string &node_name)

Construct a new Node Service Impl object.

参数

node_name – node name

NodeServiceImpl() = delete

Forbid default-constructor.

inline ~NodeServiceImpl()

Destroy the Node Service Impl object.

cyber/parameter/parameter.h

Defined in cyber/parameter/parameter.h

class apollo::cyber::Parameter

A Parameter holds an apollo::cyber::proto::Param, It’s more human-readable, you can use basic-value type and Protobuf values to construct a paramter. Parameter is identified by their name, and you can get Parameter content by call value()

Public Functions

Parameter()

Empty constructor.

explicit Parameter(const Parameter &parameter)

copy constructor

explicit Parameter(const std::string &name)

construct with paramter’s name

参数

nameParameter name

Parameter(const std::string &name, const bool bool_value)

construct with paramter’s name and bool value type

参数
  • nameParameter name

  • bool_value – bool value

Parameter(const std::string &name, const int int_value)

construct with paramter’s name and int value type

参数
  • nameParameter name

  • int_value – int value

Parameter(const std::string &name, const int64_t int_value)

construct with paramter’s name and int value type

参数
  • nameParameter name

  • int_value – int value

Parameter(const std::string &name, const float float_value)

construct with paramter’s name and float value type

参数
  • nameParameter name

  • float_value – float value

Parameter(const std::string &name, const double double_value)

construct with paramter’s name and double value type

参数
  • nameParameter name

  • double_value – double value

Parameter(const std::string &name, const std::string &string_value)

construct with paramter’s name and string value type

参数
  • nameParameter name

  • string_value – string value

Parameter(const std::string &name, const char *string_value)

construct with paramter’s name and char* value type

参数
  • nameParameter name

  • string_value – char* value

Parameter(const std::string &name, const std::string &msg_str, const std::string &full_name, const std::string &proto_desc)

use a protobuf type value to construct the parameter

参数
  • nameParameter name

  • msg_str – protobuf contents

  • full_name – the proto full name

  • proto_desc – the proto’s description

Parameter(const std::string &name, const google::protobuf::Message &msg)

use a google::protobuf::Message type value to construct the parameter

参数
  • nameParameter name

  • msg – protobuf message

void FromProtoParam(const Param &param)

Parse a cyber::proto::Param object to cyber::parameter::Parameter object.

参数

param – The cyber::proto::Param object parse from A pointer to the target Parameter object

返回

True if parse ok, otherwise False

Param ToProtoParam() const

Parse a cyber::parameter::Parameter object to cyber::proto::Param object.

返回

The target cyber::proto::Param object

inline ParamType Type() const

Get the cyber:parameter::ParamType of this object.

返回

result cyber:parameter::ParameterType

inline std::string TypeName() const

Get Paramter’s type name, i.e.

INT,DOUBLE,STRING or protobuf message’s fullname

返回

std::string the Parameter’s type name

inline std::string Descriptor() const

Get Paramter’s descriptor, only work on protobuf types.

返回

std::string the Parameter’s type name

inline const std::string Name() const

Get the Parameter name.

返回

const std::string the Parameter’s name

inline bool AsBool() const

Get Paramter as a bool value.

返回

true result

返回

false result

inline int64_t AsInt64() const

Get Paramter as an int64_t value.

返回

int64_t int64 type result

inline double AsDouble() const

et Paramter as a double value

返回

double type result

inline const std::string AsString() const

Get Paramter as a string value.

返回

const std::string Parameter’s string expression

std::string DebugString() const

show debug string

返回

std::string Parameter’s debug string

template<typename ValueType>
std::enable_if<std::is_base_of<google::protobuf::Message, ValueType>::value, ValueType>::type value() const

 @brief Translate paramter value as a protobuf::Message

 @tparam ValueType type of the value
 @return std::enable_if<
std::is_base_of<google::protobuf::Message, ValueType>::value, ValueType>::type protobuf::Message type result

template<typename ValueType>
std::enable_if<std::is_integral<ValueType>::value && !std::is_same<ValueType, bool>::value, ValueType>::type value() const

 @brief Translate paramter value to int type

 @tparam ValueType type of the value
 @return std::enable_if<std::is_integral<ValueType>::value &&
!std::is_same<ValueType, bool>::value, ValueType>::type int type result

template<typename ValueType>
std::enable_if<std::is_floating_point<ValueType>::value, ValueType>::type value() const

 @brief Translate paramter value to bool type

 @tparam ValueType type of the value
 @return std::enable_if<std::is_floating_point<ValueType>::value,
ValueType>::type floating type result

template<typename ValueType>
std::enable_if<std::is_convertible<ValueType, std::string>::value, const std::string&>::type value() const

 @brief Translate paramter value to string type

 @tparam ValueType type of the value
 @return std::enable_if<std::is_convertible<ValueType, std::string>::value,
const std::string&>::type string type result

template<typename ValueType>
std::enable_if<std::is_same<ValueType, bool>::value, bool>::type value() const

Translate paramter value to bool type.

模板参数

ValueType – type of the value

返回

std::enable_if<std::is_same<ValueType, bool>::value, bool>::type bool type result

cyber/parameter/parameter_server.h

Defined in cyber/parameter/parameter_server.h

class apollo::cyber::ParameterServer

Parameter Service is a very important function of auto-driving. If you want to set a key-value, and hope other nodes to get the value, Routing, sensor internal/external references are set by Parameter Service ParameterServer can set a parameter, and then you can get/list paramter(s) by start a ParameterClient to send responding request.

警告

You should only have one ParameterServer works

Public Functions

explicit ParameterServer(const std::shared_ptr<Node> &node)

Construct a new ParameterServer object.

参数

node – shared_ptr of the node handler

void SetParameter(const Parameter &parmeter)

Set the Parameter object.

参数

parmeter – parameter to be set

bool GetParameter(const std::string &parameter_name, Parameter *parameter)

Get the Parameter object.

参数
  • parameter_name – name of the parameer want to get

  • parameter – pointer to store parameter want to get

返回

true get parameter success

返回

false parameter not exists

void ListParameters(std::vector<Parameter> *parameters)

get all the parameters

参数

parameters – result Paramter vector

cyber/parameter/parameter_client.h

Defined in cyber/parameter/parameter_client.h

class apollo::cyber::ParameterClient

Parameter Client is used to set/get/list parameter(s) by sending a request to ParameterServer.

Public Functions

ParameterClient(const std::shared_ptr<Node> &node, const std::string &service_node_name)

Construct a new ParameterClient object.

参数
  • node – shared_ptr of the node handler

  • service_node_name – node name which provide a param services

bool GetParameter(const std::string &param_name, Parameter *parameter)

Get the Parameter object.

参数
  • param_name

  • parameter – the pointer to store

返回

true

返回

false call service fail or timeout

bool SetParameter(const Parameter &parameter)

Set the Parameter object.

参数

parameter – parameter to be set

返回

true set parameter succues

返回

false 1. call service timeout

  1. parameter not exists The corresponding log will be recorded at the same time

bool ListParameters(std::vector<Parameter> *parameters)

Get all the Parameter objects.

参数

parameters – pointer of vector to store all the parameters

返回

true

返回

false call service fail or timeout

cyber/service/service_base.h

Defined in cyber/service/service_base.h

class apollo::cyber::ServiceBase

Base class for Service.

Subclassed by apollo::cyber::Service< Request, Response >

Public Functions

inline explicit ServiceBase(const std::string &service_name)

Construct a new Service Base object.

参数

service_name – name of this Service

inline const std::string &service_name() const

Get the service name.

cyber/service/service.h

Defined in cyber/service/service.h

template<typename Request, typename Response>
class apollo::cyber::Service : public apollo::cyber::ServiceBase

Service handles Request from the Client, and send a Response to it.

tparam Request

the request type

tparam Response

the response type

Public Functions

inline Service(const std::string &node_name, const std::string &service_name, const ServiceCallback &service_callback)

Construct a new Service object.

参数
  • node_name – used to fill RoleAttribute when join the topology

  • service_name – the service name we provide

  • service_callback – reference of ServiceCallback object

inline Service(const std::string &node_name, const std::string &service_name, ServiceCallback &&service_callback)

Construct a new Service object.

参数
  • node_name – used to fill RoleAttribute when join the topology

  • service_name – the service name we provide

  • service_callback – rvalue reference of ServiceCallback object

Service() = delete

Forbid default constructing.

bool Init()

Init the Service.

virtual void destroy()

Destroy the Service.

cyber/service/client_base.h

Defined in cyber/service/client_base.h

class apollo::cyber::ClientBase

Base class of Client.

Subclassed by apollo::cyber::Client< Request, Response >

Public Functions

inline explicit ClientBase(const std::string &service_name)

Construct a new Client Base object.

参数

service_name – the service we can request

virtual void Destroy() = 0

Destroy the Client.

inline const std::string &ServiceName() const

Get the service name.

virtual bool ServiceIsReady() const = 0

Ensure whether there is any Service named service_name_

cyber/service/client.h

Defined in cyber/service/client.h

template<typename Request, typename Response>
class apollo::cyber::Client : public apollo::cyber::ClientBase

Client get Response from a responding Service by sending a Request.

警告

One Client can only request one Service

tparam Request

the Service request type

tparam Response

the Service response type

Public Functions

inline Client(const std::string &node_name, const std::string &service_name)

Construct a new Client object.

参数
  • node_name – used to fill RoleAttribute

  • service_name – service name the Client can request

Client() = delete

forbid Constructing a new Client object with empty params

bool Init()

Init the Client.

返回

true if init successfully

返回

false if init failed

SharedResponse SendRequest(SharedRequest request, const std::chrono::seconds &timeout_s = std::chrono::seconds(5))

Request the Service with a shared ptr Request type.

参数
  • request – shared ptr of Request type

  • timeout_s – request timeout, if timeout, response will be empty

返回

SharedResponse result of this request

SharedResponse SendRequest(const Request &request, const std::chrono::seconds &timeout_s = std::chrono::seconds(5))

Request the Service with a Request object.

参数
  • request – Request object

  • timeout_s – request timeout, if timeout, response will be empty

返回

SharedResponse result of this request

SharedFuture AsyncSendRequest(SharedRequest request)

Send Request shared ptr asynchronously.

SharedFuture AsyncSendRequest(const Request &request)

Send Request object asynchronously.

SharedFuture AsyncSendRequest(SharedRequest request, CallbackType &&cb)

Send Request shared ptr asynchronously and invoke cb after we get response.

参数
  • request – Request shared ptr

  • cb – callback function after we get response

返回

SharedFuture a std::future shared ptr

virtual bool ServiceIsReady() const

Is the Service is ready?

virtual void Destroy()

destroy this Client

template<typename RatioT = std::milli>
inline bool WaitForService(std::chrono::duration<int64_t, RatioT> timeout = std::chrono::duration<int64_t, RatioT>(-1))

wait for the connection with the Service established

模板参数

RatioT – timeout unit, default is std::milli

参数

timeout – wait time in unit of RatioT

返回

true if the connection established

返回

false if timeout

cyber/service_discovery/specific_manager/manager.h

Defined in cyber/service_discovery/specific_manager/channel_namager.h

class apollo::cyber::service_discovery::Manager

Base class for management of Topology elements. Manager can Join/Leave the Topology, and Listen the topology change.

Subclassed by apollo::cyber::service_discovery::ChannelManager, apollo::cyber::service_discovery::NodeManager, apollo::cyber::service_discovery::ServiceManager

Public Functions

Manager()

Construct a new Manager object.

virtual ~Manager()

Destroy the Manager object.

bool StartDiscovery(RtpsParticipant *participant)

Startup topology discovery.

参数

participant – is used to create rtps Publisher and Subscriber

返回

true if start successfully

返回

false if start fail

void StopDiscovery()

Stop topology discovery.

virtual void Shutdown()

Shutdown module.

bool Join(const RoleAttributes &attr, RoleType role, bool need_publish = true)

Join the topology.

参数
  • attr – is the attributes that will be sent to other Manager(include ourselves)

  • role – is one of RoleType enum

返回

true if Join topology successfully

返回

false if Join topology failed

bool Leave(const RoleAttributes &attr, RoleType role)

Leave the topology.

参数
  • attr – is the attributes that will be sent to other Manager(include ourselves)

  • role – if one of RoleType enum.

返回

true if Leave topology successfully

返回

false if Leave topology failed

ChangeConnection AddChangeListener(const ChangeFunc &func)

Add topology change listener, when topology changed, func will be called.

参数

func – the callback function

返回

ChangeConnection Store it to use when you want to stop listening.

void RemoveChangeListener(const ChangeConnection &conn)

Remove our listener for topology change.

参数

conn – is the return value of AddChangeListener

virtual void OnTopoModuleLeave(const std::string &host_name, int process_id) = 0

Called when a process’ topology manager instance leave.

参数
  • host_name – is the process’s host’s name

  • process_id – is the process’ id

cyber/service_discovery/specific_manager/channel_manager.h

Defined in cyber/service_discovery/specific_manager/channel_manager.h

class apollo::cyber::service_discovery::ChannelManager : public apollo::cyber::service_discovery::Manager

Topology Manager of Service related.

Public Functions

ChannelManager()

Construct a new Channel Manager object.

virtual ~ChannelManager()

Destroy the Channel Manager object.

void GetChannelNames(std::vector<std::string> *channels)

Get all channel names in the topology.

参数

channels – result vector

void GetProtoDesc(const std::string &channel_name, std::string *proto_desc)

Get the Protocol Desc of channel_name

参数
  • channel_name – channel name we want to inquire

  • proto_desc – result string, empty if inquire failed

void GetMsgType(const std::string &channel_name, std::string *msg_type)

Get the Msg Type of channel_name

参数
  • channel_name – channel name we want to inquire

  • msg_type – result string, empty if inquire failed

bool HasWriter(const std::string &channel_name)

Inquire if there is at least one Writer that publishes channel_name

参数

channel_name – channel name we want to inquire

返回

true if there is at least one Writer

返回

false if there are no Writers

void GetWriters(RoleAttrVec *writers)

Get All Writers object.

参数

writers – result RoleAttr vector

void GetWritersOfNode(const std::string &node_name, RoleAttrVec *writers)

Get the Writers Of Node object.

参数
  • node_name – node’s name we want to inquire

  • writers – result RoleAttribute vector

void GetWritersOfChannel(const std::string &channel_name, RoleAttrVec *writers)

Get the Writers Of Channel object.

参数
  • channel_name – channel’s name we want to inquire

  • writers – result RoleAttribute vector

bool HasReader(const std::string &channel_name)

Inquire if there is at least one Reader that publishes channel_name

参数

channel_name – channel name we want to inquire

返回

true if there is at least one Reader

返回

false if there are no Reader

void GetReaders(RoleAttrVec *readers)

Get All Readers object.

参数

readers – result RoleAttr vector

void GetReadersOfNode(const std::string &node_name, RoleAttrVec *readers)

Get the Readers Of Node object.

参数
  • node_name – node’s name we want to inquire

  • readers – result RoleAttribute vector

void GetReadersOfChannel(const std::string &channel_name, RoleAttrVec *readers)

Get the Readers Of Channel object.

参数
  • channel_name – channel’s name we want to inquire

  • readers – result RoleAttribute vector

void GetUpstreamOfNode(const std::string &node_name, RoleAttrVec *upstream_nodes)

Get the Upstream Of Node object.

If Node A has writer that publishes channel-1, and Node B has reader that subscribes channel-1 then A is B’s Upstream node, and B is A’s Downstream node

参数
  • node_name – node’s name we want to inquire

  • upstream_nodes – result RoleAttribute vector

void GetDownstreamOfNode(const std::string &node_name, RoleAttrVec *downstream_nodes)

Get the Downstream Of Node object.

If Node A has writer that publishes channel-1, and Node B has reader that subscribes channel-1 then A is B’s Upstream node, and B is A’s Downstream node

参数
  • node_name – node’s name we want to inquire

  • downstream_nodes – result RoleAttribute vector

FlowDirection GetFlowDirection(const std::string &lhs_node_name, const std::string &rhs_node_name)

Get the Flow Direction from lhs_node_node to rhs_node_name You can see FlowDirection’s description for more information.

返回

FlowDirection result direction

bool IsMessageTypeMatching(const std::string &lhs, const std::string &rhs)

Is lhs and rhs have same MessageType.

参数
  • lhs – the left message type to compare

  • rhs – the right message type to compare

返回

true if type matches

返回

false if type does not matches

cyber/service_discovery/specific_manager/node_manager.h

Defined in cyber/service_discovery/specific_manager/node_manager.h

class apollo::cyber::service_discovery::NodeManager : public apollo::cyber::service_discovery::Manager

Topology Manager of Node related.

Public Functions

NodeManager()

Construct a new Node Manager object.

virtual ~NodeManager()

Destroy the Node Manager object.

bool HasNode(const std::string &node_name)

Checkout whether we have node_name in topology.

参数

node_nameNode’s name we want to inquire

返回

true if this node found

返回

false if this node not exits

void GetNodes(RoleAttrVec *nodes)

Get the Nodes object.

参数

nodes – result RoleAttr vector

cyber/service_discovery/specific_manager/service_manager.h

Defined in cyber/service_discovery/specific_manager/service_manager.h

class apollo::cyber::service_discovery::ServiceManager : public apollo::cyber::service_discovery::Manager

Topology Manager of Service related.

Public Functions

ServiceManager()

Construct a new Service Manager object.

virtual ~ServiceManager()

Destroy the Service Manager object.

bool HasService(const std::string &service_name)

Inquire whether service_name exists in topology.

参数

service_name – the name we inquire

返回

true if service exists

返回

false if service not exists

void GetServers(RoleAttrVec *servers)

Get the All Server in the topology.

参数

servers – result RoleAttr vector

void GetClients(const std::string &service_name, RoleAttrVec *clients)

Get the Clients object that subscribes service_name

参数
  • service_name – Name of service you want to get

  • clients – result vector

cyber/service_discovery/topology_manager.h

Defined in cyber/service_discovery/topology_manager.h

class apollo::cyber::service_discovery::TopologyManager

elements in Cyber Node, Channel, Service, Writer, Reader, Client and Server’s relationship is presented by Topology. You can Imagine that a directed graph Node is the container of Server/Client/Writer/Reader, and they are the vertice of the graph and Channel is the Edge from Writer flow to the Reader, Service is the Edge from Server to Client. Thus we call Writer and Server Upstream, Reader and Client Downstream To generate this graph, we use TopologyManager, it has three sub managers NodeManager: You can find Nodes in this topology ChannelManager: You can find Channels in this topology, and their Writers and Readers ServiceManager: You can find Services in this topology, and their Servers and Clients TopologyManager use fast-rtps’ Participant to communicate. It can broadcast Join or Leave messages of those elements. Also, you can register you own ChangeFunc to monitor topology change

Public Functions

void Shutdown()

Shutdown the TopologyManager.

ChangeConnection AddChangeListener(const ChangeFunc &func)

To observe the topology change, you can register a ChangeFunc

参数

func – is the observe function

返回

ChangeConnection is the connection that connected to change_signal_. Used to Remove your observe function

void RemoveChangeListener(const ChangeConnection &conn)

Remove the observe function connect to change_signal_ by conn

inline NodeManagerPtr &node_manager()

Get shared_ptr for NodeManager.

inline ChannelManagerPtr &channel_manager()

Get shared_ptr for ChannelManager.

inline ServiceManagerPtr &service_manager()

Get shared_ptr for ServiceManager.

cyber/component/component.h

Defined in cyber/component/component.h

template<typename M0 = NullType, typename M1 = NullType, typename M2 = NullType, typename M3 = NullType>
class apollo::cyber::Component : public apollo::cyber::ComponentBase

The Component can process up to four channels of messages. The message type is specified when the component is created. The Component is inherited from ComponentBase. Your component can inherit from Component, and implement Init() & Proc(…), They are picked up by the CyberRT. There are 4 specialization implementations.

警告

The Init & Proc functions need to be overloaded, but don’t want to be called. They are called by the CyberRT Frame.

tparam M0

the first message.

tparam M1

the second message.

tparam M2

the third message.

tparam M3

the fourth message.

Subclassed by apollo::drivers::camera::CameraComponent, apollo::drivers::camera::CompressComponent, apollo::drivers::gnss::GnssDriverComponent, apollo::drivers::microphone::MicrophoneComponent, apollo::drivers::robosense::RobosenseComponent, apollo::drivers::smartereye::CompressComponent, apollo::drivers::smartereye::SmartereyeComponent, apollo::drivers::velodyne::CompensatorComponent, apollo::drivers::velodyne::PriSecFusionComponent, apollo::drivers::velodyne::VelodyneConvertComponent, apollo::drivers::velodyne::VelodyneDriverComponent, apollo::drivers::video::CompCameraH265Compressed

Public Functions

inline virtual bool Initialize(const ComponentConfig &config) override

init the component by protobuf object.

参数

config – which is defined in ‘cyber/proto/component_conf.proto’

返回

returns true if successful, otherwise returns false

cyber/component/timer_component.h

Defined in cyber/component/timer_component.h

class apollo::cyber::TimerComponent : public apollo::cyber::ComponentBase

TimerComponent is a timer component. Your component can inherit from Component, and implement Init() & Proc(), They are called by the CyberRT frame.

Subclassed by apollo::canbus::CanbusComponent, apollo::control::ControlComponent, apollo::cyber::Component_Timer, apollo::guardian::GuardianComponent, apollo::monitor::Monitor, apollo::prediction::FakePredictionComponent, apollo::relative_map::RelativeMapComponent, apollo::storytelling::Storytelling, apollo::third_party_perception::ThirdPartyPerceptionComponent, ManualTrafficLight, TimerComponentSample

Public Functions

virtual bool Initialize(const TimerComponentConfig &config) override

init the component by protobuf object.

参数

config – which is define in ‘cyber/proto/component_conf.proto’

返回

returns true if successful, otherwise returns false

cyber/logger/async_logger.h

Defined in cyber/logger/async_logger.h

class apollo::cyber::logger::AsyncLogger : public Logger

Wrapper for a glog Logger which asynchronously writes log messages. This class starts a new thread responsible for forwarding the messages to the logger, and performs double buffering. Writers append to the current buffer and then wake up the logger thread. The logger swaps in a new buffer and writes any accumulated messages to the wrapped Logger.

This double-buffering design dramatically improves performance, especially for logging messages which require flushing the underlying file (i.e WARNING and above for default). The flush can take a couple of milliseconds, and in some cases can even block for hundreds of milliseconds or more. With the double-buffered approach, threads can proceed with useful work while the IO thread blocks.

The semantics provided by this wrapper are slightly weaker than the default glog semantics. By default, glog will immediately (synchronously) flush WARNING and above to the underlying file, whereas here we are deferring that flush to a separate thread. This means that a crash just after a ‘LOG_WARN’ would may be missing the message in the logs, but the perf benefit is probably worth it. We do take care that a glog FATAL message flushes all buffered log messages before exiting.

警告

The logger limits the total amount of buffer space, so if the underlying log blocks for too long, eventually the threads generating the log messages will block as well. This prevents runaway memory usage.

Public Functions

void Start()

start the async logger

void Stop()

Stop the thread.

Flush() and Write() must not be called after this. NOTE: this is currently only used in tests: in real life, we enable async logging once when the program starts and then never disable it. REQUIRES: Start() must have been called.

void Write(bool force_flush, time_t timestamp, const char *message, int message_len) override

Write a message to the log.

Start() must have been called.

参数
  • force_flush – is set by the GLog library based on the configured ‘logbuflevel’ flag. Any messages logged at the configured level or higher result in ‘force_flush’ being set to true, indicating that the message should be immediately written to the log rather than buffered in memory.

  • timestamp – is the time of write a message

  • message – is the info to be written

  • message_len – is the length of message

void Flush() override

Flush any buffered messages.

uint32_t LogSize() override

Get the current LOG file size.

The return value is an approximate value since some logged data may not have been flushed to disk yet.

返回

the log file size

inline std::thread *LogThread()

get the log thead

返回

the pointer of log thread

cyber/timer/timer.h

Defined in cyber/timer/timer.h

struct apollo::cyber::TimerOption

The options of timer.

Public Functions

inline TimerOption(uint32_t period, std::function<void()> callback, bool oneshot)

Construct a new Timer Option object.

参数
  • period – The period of the timer, unit is ms

  • callback – The task that the timer needs to perform

  • oneshot – Oneshot or period

inline TimerOption()

Default constructor for initializer list.

Public Members

uint32_t period = 0

The period of the timer, unit is ms max: 512 * 64 min: 1.

std::function<void()> callback

The task that the timer needs to perform.

bool oneshot

True: perform the callback only after the first timing cycle False: perform the callback every timed period.

class apollo::cyber::Timer

Used to perform oneshot or periodic timing tasks.

Public Functions

explicit Timer(TimerOption opt)

Construct a new Timer object.

参数

optTimer option

Timer(uint32_t period, std::function<void()> callback, bool oneshot)

Construct a new Timer object.

参数
  • period – The period of the timer, unit is ms

  • callback – The tasks that the timer needs to perform

  • oneshot – True: perform the callback only after the first timing cycle False: perform the callback every timed period

void SetTimerOption(TimerOption opt)

Set the Timer Option object.

参数

opt – The timer option will be set

void Start()

Start the timer.

void Stop()

Stop the timer.

cyber/time/time.h

Defined in cyber/time/time.h

class apollo::cyber::Time

Cyber has builtin time type Time.

Public Functions

double ToSecond() const

convert time to second.

返回

return a double value unit is second.

uint64_t ToMicrosecond() const

convert time to microsecond (us).

返回

return a unit64_t value unit is us.

uint64_t ToNanosecond() const

convert time to nanosecond.

返回

return a unit64_t value unit is nanosecond.

std::string ToString() const

convert time to a string.

返回

return a string.

bool IsZero() const

determine if time is 0

返回

return true if time is 0

Public Static Functions

static Time Now()

get the current time.

返回

return the current time.

static void SleepUntil(const Time &time)

Sleep Until time.

参数

time – the Time object.

cyber/record/header_builder.h

Defined in cyber/record/header_builder.h

class apollo::cyber::record::HeaderBuilder

The builder of record header.

Public Static Functions

static proto::Header GetHeaderWithSegmentParams(const uint64_t segment_interval, const uint64_t segment_raw_size)

Build a record header with customized max interval time (ns) and max raw size (byte) for segment.

参数
  • segment_interval

  • segment_raw_size

返回

A customized record header.

static proto::Header GetHeaderWithChunkParams(const uint64_t chunk_interval, const uint64_t chunk_raw_size)

Build a record header with customized max interval time (ns) and max raw size (byte) for chunk.

参数
  • chunk_interval

  • chunk_raw_size

返回

A customized record header.

static proto::Header GetHeader()

Build a default record header.

返回

A default record header.

cyber/record/record_base.h

Defined in cyber/record/record_base.h

class apollo::cyber::record::RecordBase

Base class for record reader and writer.

Subclassed by apollo::cyber::record::RecordReader, apollo::cyber::record::RecordWriter

Public Functions

virtual ~RecordBase() = default

Destructor.

virtual uint64_t GetMessageNumber(const std::string &channel_name) const = 0

Get message number by channel name.

参数

channel_name

返回

Message number.

virtual const std::string &GetMessageType(const std::string &channel_name) const = 0

Get message type by channel name.

参数

channel_name

返回

Message type.

virtual const std::string &GetProtoDesc(const std::string &channel_name) const = 0

Get proto descriptor string by channel name.

参数

channel_name

返回

Proto descriptor string by channel name.

virtual std::set<std::string> GetChannelList() const = 0

Get channel list.

返回

List container with all channel name string.

inline const proto::Header &GetHeader() const

Get record header.

返回

Record header.

inline const std::string GetFile() const

Get record file path.

返回

Record file path.

cyber/record/record_message.h

Defined in cyber/record/record_message.h

struct apollo::cyber::record::RecordMessage

Basic data struct of record message.

Public Functions

inline RecordMessage()

The constructor.

inline RecordMessage(const std::string &name, const std::string &message, uint64_t msg_time)

The constructor.

参数
  • name

  • message

  • msg_time

Public Members

std::string channel_name

The channel name of the message.

std::string content

The content of the message.

uint64_t time

The time (nanosecond) of the message.

cyber/record/record_reader.h

Defined in cyber/record/record_reader.h

class apollo::cyber::record::RecordReader : public apollo::cyber::record::RecordBase

The record reader.

Public Functions

explicit RecordReader(const std::string &file)

The constructor with record file path as parameter.

参数

file

virtual ~RecordReader()

The destructor.

inline bool IsValid() const

Is this record reader is valid.

返回

True for valid, false for not.

bool ReadMessage(RecordMessage *message, uint64_t begin_time = 0, uint64_t end_time = std::numeric_limits<uint64_t>::max())

Read one message from reader.

参数
  • message

  • begin_time

  • end_time

返回

True for success, false for not.

void Reset()

Reset the message index of record reader.

virtual uint64_t GetMessageNumber(const std::string &channel_name) const override

Get message number by channel name.

参数

channel_name

返回

Message number.

virtual const std::string &GetMessageType(const std::string &channel_name) const override

Get message type by channel name.

参数

channel_name

返回

Message type.

virtual const std::string &GetProtoDesc(const std::string &channel_name) const override

Get proto descriptor string by channel name.

参数

channel_name

返回

Proto descriptor string by channel name.

virtual std::set<std::string> GetChannelList() const override

Get channel list.

返回

List container with all channel name string.

cyber/record/record_writer.h

Defined in cyber/record/record_writer.h

class apollo::cyber::record::RecordWriter : public apollo::cyber::record::RecordBase

The record writer.

Public Functions

RecordWriter()

The default constructor.

explicit RecordWriter(const proto::Header &header)

The constructor with record header as parameter.

参数

header

virtual ~RecordWriter()

Virtual Destructor.

bool Open(const std::string &file)

Open a record to write.

参数

file

返回

True for success, false for fail.

void Close()

Clean the record.

bool WriteChannel(const std::string &channel_name, const std::string &message_type, const std::string &proto_desc)

Write a channel to record.

参数
  • channel_name

  • message_type

  • proto_desc

返回

True for success, false for fail.

template<typename MessageT>
bool WriteMessage(const std::string &channel_name, const MessageT &message, const uint64_t time_nanosec, const std::string &proto_desc = "")

Write a message to record.

模板参数

MessageT

参数
  • channel_name

  • message

  • time_nanosec

  • proto_desc

返回

True for success, false for fail.

bool SetSizeOfFileSegmentation(uint64_t size_kilobytes)

Set max size (KB) to segment record file.

参数

size_kilobytes

返回

True for success, false for fail.

bool SetIntervalOfFileSegmentation(uint64_t time_sec)

Set max interval (Second) to segment record file.

参数

time_sec

返回

True for success, false for fail.

virtual uint64_t GetMessageNumber(const std::string &channel_name) const override

Get message number by channel name.

参数

channel_name

返回

Message number.

virtual const std::string &GetMessageType(const std::string &channel_name) const override

Get message type by channel name.

参数

channel_name

返回

Message type.

virtual const std::string &GetProtoDesc(const std::string &channel_name) const override

Get proto descriptor string by channel name.

参数

channel_name

返回

Proto descriptor string by channel name.

virtual std::set<std::string> GetChannelList() const override

Get channel list.

返回

List container with all channel name string.

bool IsNewChannel(const std::string &channel_name) const

Is a new channel recording or not.

返回

True for yes, false for no.

cyber/record/record_viewer.h

Defined in cyber/record/record_viewer.h

class apollo::cyber::record::RecordViewer

The record viewer.

Public Functions

RecordViewer(const RecordReaderPtr &reader, uint64_t begin_time = 0, uint64_t end_time = std::numeric_limits<uint64_t>::max(), const std::set<std::string> &channels = {})

The constructor with single reader.

参数
  • reader

  • begin_time

  • end_time

  • channels

RecordViewer(const std::vector<RecordReaderPtr> &readers, uint64_t begin_time = 0, uint64_t end_time = std::numeric_limits<uint64_t>::max(), const std::set<std::string> &channels = std::set<std::string>())

The constructor with multiple readers.

参数
  • readers

  • begin_time

  • end_time

  • channels

bool IsValid() const

Is this record reader is valid.

返回

True for valid, false for not.

inline uint64_t begin_time() const

Get begin time.

返回

Begin time (nanoseconds).

inline uint64_t end_time() const

Get end time.

返回

end time (nanoseconds).

inline std::set<std::string> GetChannelList() const

Get channel list.

返回

List container with all channel name string.

Iterator begin()

Get the begin iterator.

返回

The begin iterator.

Iterator end()

Get the end iterator.

返回

The end iterator.

class Iterator : public std::iterator<std::input_iterator_tag, RecordMessage, int, RecordMessage*, RecordMessage&>

The iterator.

Public Functions

explicit Iterator(RecordViewer *viewer, bool end = false)

The constructor of iterator with viewer.

参数
  • viewer

  • end

inline Iterator()

The default constructor of iterator.

inline virtual ~Iterator()

The default destructor of iterator.

bool operator==(Iterator const &other) const

Overloading operator ==.

参数

other

返回

The result.

bool operator!=(const Iterator &rhs) const

Overloading operator !=.

参数

other

返回

The result.

Iterator &operator++()

Overloading operator ++.

返回

The result.

pointer operator->()

Overloading operator ->.

返回

The pointer.

reference operator*()

Overloading operator *.

返回

The reference.