cyber/node/node.h

Defined in cyber/node/node.h

class 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.

Warning

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.

Warning

duplicate node name is not allowed in the topo.

template<typename MessageT>
auto CreateWriter(const proto::RoleAttributes &role_attr)

Create a Writer with specific message type.

Return

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

Template Parameters
  • MessageT: Message Type

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

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

Create a Writer with specific message type.

Return

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

Template Parameters
  • MessageT: Message Type

Parameters
  • channel_name: the channel name to be published.

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

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

Return

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

Template Parameters
  • MessageT: Message Type

Parameters
  • channel_name: the channel of the reader subscribed.

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

template<typename MessageT>
auto CreateReader(const ReaderConfig &config, const CallbackFunc<MessageT> &reader_func = nullptr)

Create a Reader with specific message type with reader config.

Return

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

Template Parameters
  • MessageT: Message Type

Parameters
  • config: instance of ReaderConfig, include channel name, qos and pending queue size

  • reader_func: invoked when message receive

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

Create a Reader object with RoleAttributes

Return

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

Template Parameters
  • MessageT: Message Type

Parameters
  • role_attr: instance of RoleAttributes, includes channel name, qos, etc.

  • reader_func: invoked when message receive

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

Create a Service object with specific service_name

Return

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

Template Parameters
  • Request: Message Type of the Request

  • Response: Message Type of the Response

Parameters
  • service_name: specific service name to a serve

  • service_callback: invoked when a service is called

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

Create a Client object to request Service with service_name

Return

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

Template Parameters
  • Request: Message Type of the Request

  • Response: Message Type of the Response

Parameters
  • service_name: specific service name to a Service

void Observe()

Observe all readers’ data.

void ClearData()

clear all readers’ data

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

Get the Reader object that subscribe channel_name

Return

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

Template Parameters
  • MessageT: Message Type

Parameters
  • channel_name: channel name

cyber/node/reader_base.h

Defined in cyber/node/reader_base.h

class 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.

Return

true if init successfully

Return

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.

Return

true if data container is empty

Return

false if data container has data

virtual bool HasReceived() const = 0

Query whether we have received data since last clear.

Return

true if the reader has received data

Return

false if the reader has not received data

virtual double GetDelaySec() const = 0

Get time interval of since last receive message.

Return

double seconds delay

virtual uint32_t PendingQueueSize() const = 0

Get the value of pending queue size.

Return

uint32_t result value

virtual bool HasWriter()

Query is there any writer that publish the subscribed channel.

Return

true if there is at least one Writer publish the channel

Return

false if there is no Writer publish the channel

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

Get all writers pushlish the channel we subscribes.

Parameters
  • writers: result RoleAttributes vector

const std::string &GetChannelName() const

Get Reader’s Channel name.

Return

const std::string& channel name

uint64_t ChannelId() const

Get Reader’s Channel id.

Return

uint64_t channel id

const proto::QosProfile &QosProfile() const

Get qos profile.

You can see qos description

Return

const proto::QosProfile& result qos

bool IsInit() const

Query whether the Reader is initialized.

Return

true if the Reader has been inited

Return

false if the Reader has not been inited

cyber/node/reader.h

Defined in cyber/node/reader.h

template<typename MessageT>
class 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

    Warning

    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.

Public Functions

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.

Warning

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

Parameters
  • 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.

bool Init()

Init Reader.

Return

true if init successfully

Return

false if init failed

void Shutdown()

Shutdown Reader.

void Observe()

Get All data that Blocker stores.

void ClearData()

Clear Blocker’s data.

bool HasReceived() const

Query whether we have received data since last clear.

Return

true if the reader has received data

Return

false if the reader has not received data

bool Empty() const

Query whether the Reader has data to be handled.

Return

true if blocker is empty

Return

false if blocker has data

double GetDelaySec() const

Get time interval of since last receive message.

Return

double seconds delay

uint32_t PendingQueueSize() const

Get pending_queue_size configuration.

Return

uint32_t the value of pending queue size

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

Push msg to Blocker’s PublishQueue

Parameters
  • msg: message ptr to be pushed

void SetHistoryDepth(const uint32_t &depth)

Set Blocker’s PublishQueue’s capacity to depth

Parameters
  • depth: the value you want to set

uint32_t GetHistoryDepth() const

Get Blocker’s PublishQueue’s capacity.

Return

uint32_t depth of the history

std::shared_ptr<MessageT> GetLatestObserved() const

Get the latest message we Observe

Return

std::shared_ptr<MessageT> the latest message

std::shared_ptr<MessageT> GetOldestObserved() const

Get the oldest message we Observe

Return

std::shared_ptr<MessageT> the oldest message

virtual Iterator Begin() const

Get the begin iterator of ObserveQueue, used to traverse.

Return

Iterator begin iterator

virtual Iterator End() const

Get the end iterator of ObserveQueue, used to traverse.

Return

Iterator begin iterator

bool HasWriter()

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

Return

true if the channel has writer

Return

false if the channel has no writer

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

Get all writers pushlish the channel we subscribes.

Parameters
  • writers: result vector of RoleAttributes

cyber/node/writer_base.h

Defined in cyber/node/writer_base.h

class WriterBase

Base class for a Writer.

A Writer is an object to send messages through a ‘Channel’

Warning

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

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

Public Functions

WriterBase(const proto::RoleAttributes &role_attr)

Construct a new Writer Base object.

Parameters
  • role_attr: role attributes for this Writer

virtual bool Init() = 0

Init the Writer.

Return

true if init success

Return

false if init failed

virtual void Shutdown() = 0

Shutdown the Writer.

virtual bool HasReader()

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

Return

true if the channel has reader

Return

false if the channel has no reader

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

Get all Readers that subscriber our writing channel.

Parameters
  • readers: result vector of RoleAttributes

const std::string &GetChannelName() const

Get Writer’s Channel name.

Return

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

bool IsInit() const

Is Writer initialized?

Return

true if the Writer is inited

Return

false if the Write is not inited

cyber/node/writer.h

Defined in cyber/node/writer.h

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

Public Functions

Writer(const proto::RoleAttributes &role_attr)

Construct a new Writer object.

Parameters
  • role_attr: we use RoleAttributes to identify a Writer

bool Init()

Init the Writer.

Return

true if init successfully

Return

false if init failed

void Shutdown()

Shutdown the Writer.

bool Write(const MessageT &msg)

Write a MessageT instance.

Return

true if write successfully

Return

false if write failed

Parameters
  • msg: the message we want to write

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

Write a shared ptr of MessageT.

Return

true if write successfully

Return

false if write failed

Parameters
  • msg_ptr: the message shared ptr we want to write

bool HasReader()

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

Return

true if the channel has reader

Return

false if the channel has no reader

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

Get all Readers that subscriber our writing channel.

Parameters
  • readers: vector result of RoleAttributes

cyber/node/node_channel_impl.h

Defined in cyber/node/node_channel_impl.h

struct ReaderConfig

Public Functions

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 NodeChannelImpl

The implementation for Node to create Objects connected by Channels.

e.g. Channel Reader and Writer

Public Functions

NodeChannelImpl(const std::string &node_name)

Construct a new Node Channel Impl object.

Parameters
  • node_name: node name

virtual ~NodeChannelImpl()

Destroy the Node Channel Impl object.

const std::string &NodeName() const

get name of this node

Return

const std::string& actual node name

cyber/node/node_service_impl.h

Defined in cyber/node/node_service_impl.h

class NodeServiceImpl

The implementation for Node to create Objects connected by Param.

e.g. Param Server and Client

Public Functions

NodeServiceImpl(const std::string &node_name)

Construct a new Node Service Impl object.

Parameters
  • node_name: node name

NodeServiceImpl()

Forbid default-constructor.

~NodeServiceImpl()

Destroy the Node Service Impl object.

cyber/parameter/parameter.h

Defined in cyber/parameter/parameter.h

class 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.

Parameter(const Parameter &parameter)

copy constructor

Parameter(const std::string &name)

construct with paramter’s name

Parameters

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

construct with paramter’s name and bool value type

Parameters
  • name: Parameter name

  • bool_value: bool value

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

construct with paramter’s name and int value type

Parameters

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

construct with paramter’s name and int value type

Parameters

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

construct with paramter’s name and float value type

Parameters
  • name: Parameter name

  • float_value: float value

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

construct with paramter’s name and double value type

Parameters
  • name: Parameter name

  • double_value: double value

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

construct with paramter’s name and string value type

Parameters
  • name: Parameter name

  • string_value: string value

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

construct with paramter’s name and char* value type

Parameters
  • name: Parameter 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

Parameters
  • name: Parameter 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

Parameters

void FromProtoParam(const Param &param)

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

Return

True if parse ok, otherwise False

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

Param ToProtoParam() const

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

Return

The target cyber::proto::Param object

ParamType Type() const

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

Return

result cyber:parameter::ParameterType

std::string TypeName() const

Get Paramter’s type name, i.e.

INT,DOUBLE,STRING or protobuf message’s fullname

Return

std::string the Parameter’s type name

std::string Descriptor() const

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

Return

std::string the Parameter’s type name

const std::string Name() const

Get the Parameter name.

Return

const std::string the Parameter’s name

bool AsBool() const

Get Paramter as a bool value.

Return

true result

Return

false result

int64_t AsInt64() const

Get Paramter as an int64_t value.

Return

int64_t int64 type result

double AsDouble() const

et Paramter as a double value

Return

double type result

const std::string AsString() const

Get Paramter as a string value.

Return

const std::string Parameter’s string expression

std::string DebugString() const

show debug string

Return

std::string Parameter’s debug string

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

Translate paramter value as a protobuf::Message.

Return

std::enable_if< std::is_base_of<google::protobuf::Message, ValueType>::value, ValueType>::type protobuf::Message type result

Template Parameters
  • ValueType: type of the value

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

Translate paramter value to int type.

Return

std::enable_if<std::is_integral<ValueType>::value && !std::is_same<ValueType, bool>::value, ValueType>::type int type result

Template Parameters
  • ValueType: type of the value

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

Translate paramter value to bool type.

Return

std::enable_if<std::is_floating_point<ValueType>::value, ValueType>::type floating type result

Template Parameters
  • ValueType: type of the value

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

Translate paramter value to string type.

Return

std::enable_if<std::is_convertible<ValueType, std::string>::value, const std::string&>::type string type result

Template Parameters
  • ValueType: type of the value

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

Translate paramter value to bool type.

Return

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

Template Parameters
  • ValueType: type of the value

cyber/parameter/parameter_server.h

Defined in cyber/parameter/parameter_server.h

class 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

Warning

You should only have one ParameterServer works

Public Functions

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

Construct a new ParameterServer object.

Parameters
  • node: shared_ptr of the node handler

void SetParameter(const Parameter &parmeter)

Set the Parameter object.

Parameters
  • parmeter: parameter to be set

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

Get the Parameter object.

Return

true get parameter success

Return

false parameter not exists

Parameters
  • parameter_name: name of the parameer want to get

  • parameter: pointer to store parameter want to get

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

get all the parameters

Parameters
  • parameters: result Paramter vector

cyber/parameter/parameter_client.h

Defined in cyber/parameter/parameter_client.h

class 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.

Parameters
  • 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.

Return

true

Return

false call service fail or timeout

Parameters
  • param_name:

  • parameter: the pointer to store

bool SetParameter(const Parameter &parameter)

Set the Parameter object.

Return

true set parameter succues

Return

false 1. call service timeout

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

Parameters
  • parameter: parameter to be set

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

Get all the Parameter objects.

Return

true

Return

false call service fail or timeout

Parameters
  • parameters: pointer of vector to store all the parameters

cyber/service/service_base.h

Defined in cyber/service/service_base.h

class ServiceBase

Base class for Service.

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

Public Functions

ServiceBase(const std::string &service_name)

Construct a new Service Base object.

Parameters
  • service_name: name of this Service

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 Service : public apollo::cyber::ServiceBase

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

Template Parameters
  • Request: the request type

  • Response: the response type

Public Functions

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

Construct a new Service object.

Parameters
  • node_name: used to fill RoleAttribute when join the topology

  • service_name: the service name we provide

  • service_callback: reference of ServiceCallback object

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

Construct a new Service object.

Parameters
  • 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()

Forbid default constructing.

bool Init()

Init the Service.

void destroy()

Destroy the Service.

cyber/service/client_base.h

Defined in cyber/service/client_base.h

class ClientBase

Base class of Client.

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

Public Functions

ClientBase(const std::string &service_name)

Construct a new Client Base object.

Parameters
  • service_name: the service we can request

virtual void Destroy() = 0

Destroy the Client.

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 Client : public apollo::cyber::ClientBase

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

Warning

One Client can only request one Service

Template Parameters
  • Request: the Service request type

  • Response: the Service response type

Public Functions

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

Construct a new Client object.

Parameters
  • node_name: used to fill RoleAttribute

  • service_name: service name the Client can request

Client()

forbid Constructing a new Client object with empty params

bool Init()

Init the Client.

Return

true if init successfully

Return

false if init failed

Client<Request, Response>::SharedResponse SendRequest(SharedRequest request, const std::chrono::seconds &timeout_s = std::chrono::seconds(5))

Request the Service with a shared ptr Request type.

Return

SharedResponse result of this request

Parameters
  • request: shared ptr of Request type

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

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

Request the Service with a Request object.

Return

SharedResponse result of this request

Parameters
  • request: Request object

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

Client<Request, Response>::SharedFuture AsyncSendRequest(SharedRequest request)

Send Request shared ptr asynchronously.

Client<Request, Response>::SharedFuture AsyncSendRequest(const Request &request)

Send Request object asynchronously.

Client<Request, Response>::SharedFuture AsyncSendRequest(SharedRequest request, CallbackType &&cb)

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

Return

SharedFuture a std::future shared ptr

Parameters
  • request: Request shared ptr

  • cb: callback function after we get response

bool ServiceIsReady() const

Is the Service is ready?

void Destroy()

destroy this Client

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

wait for the connection with the Service established

Return

true if the connection established

Return

false if timeout

Template Parameters
  • RatioT: timeout unit, default is std::milli

Parameters
  • timeout: wait time in unit of RatioT

cyber/service_discovery/specific_manager/manager.h

Defined in cyber/service_discovery/specific_manager/channel_namager.h

class 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.

Return

true if start successfully

Return

false if start fail

Parameters
  • participant: is used to create rtps Publisher and Subscriber

void StopDiscovery()

Stop topology discovery.

virtual void Shutdown()

Shutdown module.

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

Join the topology.

Return

true if Join topology successfully

Return

false if Join topology failed

Parameters
  • attr: is the attributes that will be sent to other Manager(include ourselves)

  • role: is one of RoleType enum

bool Leave(const RoleAttributes &attr, RoleType role)

Leave the topology.

Return

true if Leave topology successfully

Return

false if Leave topology failed

Parameters
  • attr: is the attributes that will be sent to other Manager(include ourselves)

  • role: if one of RoleType enum.

ChangeConnection AddChangeListener(const ChangeFunc &func)

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

Return

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

Parameters
  • func: the callback function

void RemoveChangeListener(const ChangeConnection &conn)

Remove our listener for topology change.

Parameters
  • 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.

Parameters
  • 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 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.

Parameters
  • channels: result vector

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

Get the Protocol Desc of channel_name

Parameters
  • 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

Parameters
  • 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

Return

true if there is at least one Writer

Return

false if there are no Writers

Parameters
  • channel_name: channel name we want to inquire

void GetWriters(RoleAttrVec *writers)

Get All Writers object.

Parameters
  • writers: result RoleAttr vector

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

Get the Writers Of Node object.

Parameters
  • 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.

Parameters
  • 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

Return

true if there is at least one Reader

Return

false if there are no Reader

Parameters
  • channel_name: channel name we want to inquire

void GetReaders(RoleAttrVec *readers)

Get All Readers object.

Parameters
  • readers: result RoleAttr vector

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

Get the Readers Of Node object.

Parameters
  • 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.

Parameters
  • 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

Parameters
  • 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

Parameters
  • 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.

Return

FlowDirection result direction

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

Is lhs and rhs have same MessageType.

Return

true if type matches

Return

false if type does not matches

Parameters
  • lhs: the left message type to compare

  • rhs: the right message type to compare

cyber/service_discovery/specific_manager/node_manager.h

Defined in cyber/service_discovery/specific_manager/node_manager.h

class 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.

Return

true if this node found

Return

false if this node not exits

Parameters
  • node_name: Node’s name we want to inquire

void GetNodes(RoleAttrVec *nodes)

Get the Nodes object.

Parameters
  • nodes: result RoleAttr vector

cyber/service_discovery/specific_manager/service_manager.h

Defined in cyber/service_discovery/specific_manager/service_manager.h

class 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.

Return

true if service exists

Return

false if service not exists

Parameters
  • service_name: the name we inquire

void GetServers(RoleAttrVec *servers)

Get the All Server in the topology.

Parameters
  • servers: result RoleAttr vector

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

Get the Clients object that subscribes service_name

Parameters
  • 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 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

Return

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

Parameters
  • func: is the observe function

void RemoveChangeListener(const ChangeConnection &conn)

Remove the observe function connect to change_signal_ by conn

NodeManagerPtr &node_manager()

Get shared_ptr for NodeManager.

ChannelManagerPtr &channel_manager()

Get shared_ptr for ChannelManager.

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 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.

Warning

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

Template Parameters
  • M0: the first message.

  • M1: the second message.

  • M2: the third message.

  • M3: the fourth message.

Public Functions

bool Initialize(const ComponentConfig &config)

init the component by protobuf object.

Return

returns true if successful, otherwise returns false

Parameters
  • config: which is defined in ‘cyber/proto/component_conf.proto’

cyber/component/timer_component.h

Defined in cyber/component/timer_component.h

class 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.

Public Functions

bool Initialize(const TimerComponentConfig &config)

init the component by protobuf object.

Return

returns true if successful, otherwise returns false

Parameters
  • config: which is define in ‘cyber/proto/component_conf.proto’

cyber/logger/async_logger.h

Defined in cyber/logger/async_logger.h

class 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.

Warning

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)

Write a message to the log.

Start() must have been called.

Parameters
  • 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()

Flush any buffered messages.

uint32_t LogSize()

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.

Return

the log file size

const std::thread *LogThread() const

get the log thead

Return

the pointer of log thread

cyber/timer/timer.h

Defined in cyber/timer/timer.h

struct TimerOption

The options of timer.

Public Functions

TimerOption(uint32_t period, std::function<void()> callbackbool oneshot, )

Construct a new Timer Option object.

Parameters
  • period: The period of the timer, unit is ms

  • callback: The task that the timer needs to perform

  • oneshot: Oneshot or period

TimerOption()

Default onstructor 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 Timer

Used to perform oneshot or periodic timing tasks.

Public Functions

Timer(TimerOption opt)

Construct a new Timer object.

Parameters

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

Construct a new Timer object.

Parameters
  • 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.

Parameters
  • 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 Time

Cyber has builtin time type Time.

Public Functions

double ToSecond() const

convert time to second.

Return

return a double value unit is second.

uint64_t ToNanosecond() const

convert time to nanosecond.

Return

return a unit64_t value unit is nanosecond.

std::string ToString() const

convert time to a string.

Return

return a string.

bool IsZero() const

determine if time is 0

Return

return true if time is 0

Public Static Functions

static Time Now()

get the current time.

Return

return the current time.

static void SleepUntil(const Time &time)

Sleep Until time.

Parameters
  • time: the Time object.

cyber/record/header_builder.h

Defined in cyber/record/header_builder.h

class HeaderBuilder

The builder of record header.

Public Static Functions

static 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.

Return

A customized record header.

Parameters
  • segment_interval:

  • segment_raw_size:

static 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.

Return

A customized record header.

Parameters
  • chunk_interval:

  • chunk_raw_size:

static Header GetHeader()

Build a default record header.

Return

A default record header.

cyber/record/record_base.h

Defined in cyber/record/record_base.h

class RecordBase

Base class for record reader and writer.

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

Public Functions

virtual ~RecordBase()

Destructor.

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

Get message number by channel name.

Return

Message number.

Parameters
  • channel_name:

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

Get message type by channel name.

Return

Message type.

Parameters
  • channel_name:

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

Get proto descriptor string by channel name.

Return

Proto descriptor string by channel name.

Parameters
  • channel_name:

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

Get channel list.

Return

List container with all channel name string.

const proto::Header &GetHeader() const

Get record header.

Return

Record header.

const std::string GetFile() const

Get record file path.

Return

Record file path.

cyber/record/record_message.h

Defined in cyber/record/record_message.h

struct RecordMessage

Basic data struct of record message.

Public Functions

RecordMessage()

The constructor.

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

The constructor.

Parameters
  • 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 RecordReader : public apollo::cyber::record::RecordBase

The record reader.

Public Functions

RecordReader(const std::string &file)

The constructor with record file path as parameter.

Parameters
  • file:

virtual ~RecordReader()

The destructor.

bool IsValid() const

Is this record reader is valid.

Return

True for valid, false for not.

bool ReadMessage(RecordMessage *message, uint64_t begin_time = 0, uint64_t end_time = UINT64_MAX)

Read one message from reader.

Return

True for success, flase for not.

Parameters
  • message:

  • begin_time:

  • end_time:

void Reset()

Reset the message index of record reader.

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

Get message number by channel name.

Return

Message number.

Parameters
  • channel_name:

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

Get message type by channel name.

Return

Message type.

Parameters
  • channel_name:

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

Get proto descriptor string by channel name.

Return

Proto descriptor string by channel name.

Parameters
  • channel_name:

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

Get channel list.

Return

List container with all channel name string.

cyber/record/record_writer.h

Defined in cyber/record/record_writer.h

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

The record writer.

Public Functions

RecordWriter()

The default constructor.

RecordWriter(const proto::Header &header)

The constructor with record header as parameter.

Parameters
  • header:

virtual ~RecordWriter()

Virtual Destructor.

bool Open(const std::string &file)

Open a record to write.

Return

True for success, false for fail.

Parameters
  • file:

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.

Return

True for success, false for fail.

Parameters
  • channel_name:

  • message_type:

  • proto_desc:

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.

Return

True for success, false for fail.

Template Parameters
  • MessageT:

Parameters
  • channel_name:

  • message:

  • time_nanosec:

  • proto_desc:

bool SetSizeOfFileSegmentation(uint64_t size_kilobytes)

Set max size (KB) to segment record file.

Return

True for success, false for fail.

Parameters
  • size_kilobytes:

bool SetIntervalOfFileSegmentation(uint64_t time_sec)

Set max interval (Second) to segment record file.

Return

True for success, false for fail.

Parameters
  • time_sec:

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

Get message number by channel name.

Return

Message number.

Parameters
  • channel_name:

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

Get message type by channel name.

Return

Message type.

Parameters
  • channel_name:

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

Get proto descriptor string by channel name.

Return

Proto descriptor string by channel name.

Parameters
  • channel_name:

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

Get channel list.

Return

List container with all channel name string.

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

Is a new channel recording or not.

Return

True for yes, false for no.

cyber/record/record_viewer.h

Defined in cyber/record/record_viewer.h

class RecordViewer

The record viewer.

Public Functions

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

The constructor with single reader.

Parameters
  • reader:

  • begin_time:

  • end_time:

  • channels:

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

The constructor with multiple readers.

Parameters
  • readers:

  • begin_time:

  • end_time:

  • channels:

bool IsValid() const

Is this record reader is valid.

Return

True for valid, false for not.

uint64_t begin_time() const

Get begin time.

Return

Begin time (nanoseconds).

uint64_t end_time() const

Get end time.

Return

end time (nanoseconds).

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

Get channel list.

Return

List container with all channel name string.

Iterator begin()

Get the begin iterator.

Return

The begin iterator.

Iterator end()

Get the end iterator.

Return

The end iterator.

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

The iterator.

Public Functions

Iterator(RecordViewer *viewer, bool end = false)

The constructor of iterator with viewer.

Parameters
  • viewer:

  • end:

Iterator()

The default constructor of iterator.

virtual ~Iterator()

The default destructor of iterator.

bool operator==(Iterator const &other) const

Overloading operator ==.

Return

The result.

Parameters
  • other:

bool operator!=(const Iterator &rhs) const

Overloading operator !=.

Return

The result.

Parameters
  • other:

Iterator &operator++()

Overloading operator ++.

Return

The result.

pointer operator->()

Overloading operator ->.

Return

The pointer.

reference operator*()

Overloading operator *.

Return

The reference.