Namespaces | Classes | Typedefs | Functions | Variables
ros Namespace Reference

Namespaces

 console
 
 debug
 
 file_log
 internal
 
 init_options
 
 master
 Contains functions which allow you to query information about the master.
 
 message_operations
 
 message_traits
 
 names
 Contains functions which allow you to manipulate ROS names.
 
 network
 internal
 
 package
 
 param
 Contains functions which allow you to query the parameter server.
 
 serialization
 
 service
 Contains functions for querying information about and calling a service.
 
 service_traits
 
 this_node
 Contains functions which provide information about this process' ROS node.
 
 topic
 
 xmlrpc
 internal
 

Classes

struct  AdvertiseOptions
 Encapsulates all options available for creating a Publisher. More...
 
struct  AdvertiseServiceOptions
 Encapsulates all options available for creating a ServiceServer. More...
 
class  AsyncSpinner
 AsyncSpinner is a spinner that does not conform to the abstract Spinner interface. Instead, it spins asynchronously when you call start(), and stops when either you call stop(), ros::shutdown() is called, or its destructor is called. More...
 
class  AsyncSpinnerImpl
 
class  ASyncXMLRPCConnection
 
class  CachedXmlRpcClient
 
class  CallbackInterface
 Abstract interface for items which can be added to a CallbackQueueInterface. More...
 
class  CallbackQueue
 This is the default implementation of the ros::CallbackQueueInterface. More...
 
class  CallbackQueueInterface
 Abstract interface for a queue used to handle all callbacks within roscpp. More...
 
class  ConflictingSubscriptionException
 Thrown when a second (third,...) subscription is attempted with conflicting arguments. More...
 
class  Connection
 Encapsulates a connection to a remote host, independent of the transport type. More...
 
class  ConnectionManager
 
struct  DefaultMessageCreator
 
class  Duration
 
class  DurationBase
 
class  Exception
 
class  Header
 
class  IntraProcessPublisherLink
 Handles a connection to a single publisher on a given topic. Receives messages from a publisher and hands them off to its parent Subscription. More...
 
class  IntraProcessSubscriberLink
 SubscriberLink handles broadcasting messages to a single subscriber on a single topic. More...
 
class  InvalidNameException
 Thrown when an invalid graph resource name is specified to any roscpp function. More...
 
class  InvalidNodeNameException
 Thrown when an invalid node name is specified to ros::init() More...
 
class  InvalidParameterException
 Thrown when an invalid parameter is passed to a method. More...
 
class  InvalidPortException
 Thrown when an invalid port is specified. More...
 
class  MessageDeserializer
 
class  MessageEvent
 
class  MultiThreadedSpinner
 Spinner which spins in multiple threads. More...
 
class  NodeHandle
 roscpp's interface for creating subscribers, publishers, etc. More...
 
class  NodeHandleBackingCollection
 
class  NoHighPerformanceTimersException
 
struct  ParameterAdapter
 Generally not for outside use. Adapts a function parameter type into the message type, event type and parameter. Allows you to retrieve a parameter type from an event type. More...
 
struct  ParameterAdapter< boost::shared_ptr< M > >
 
struct  ParameterAdapter< boost::shared_ptr< M const > >
 
struct  ParameterAdapter< const boost::shared_ptr< M > & >
 
struct  ParameterAdapter< const boost::shared_ptr< M const > & >
 
struct  ParameterAdapter< const M & >
 
struct  ParameterAdapter< const ros::MessageEvent< M > & >
 
struct  ParameterAdapter< const ros::MessageEvent< M const > & >
 
class  PeerConnDisconnCallback
 
class  PollManager
 
class  PollSet
 Manages a set of sockets being polled through the poll() function call. More...
 
class  Publication
 A Publication manages an advertised topic. More...
 
class  Publisher
 Manages an advertisement on a specific topic. More...
 
class  PublisherLink
 Handles a connection to a single publisher on a given topic. Receives messages from a publisher and hands them off to its parent Subscription. More...
 
class  Rate
 
class  ROSOutAppender
 
class  SerializedMessage
 
class  ServiceCallback
 
class  ServiceCallbackHelper
 Abstract base class used by service servers to deal with concrete message types through a common interface. This is one part of the roscpp API that is not fully stable, so overloading this class is not recommended. More...
 
struct  ServiceCallbackHelperCallParams
 
class  ServiceCallbackHelperT
 Concrete generic implementation of ServiceCallbackHelper for any normal service type. More...
 
class  ServiceClient
 Provides a handle-based interface to service client connections. More...
 
class  ServiceClientLink
 Handles a connection to a single incoming service client. More...
 
struct  ServiceClientOptions
 Encapsulates all options available for creating a ServiceClient. More...
 
class  ServiceEvent
 Event type for services, ros::ServiceEvent<MReq, MRes>& can be used in your callback instead of MReq&, MRes&. More...
 
class  ServiceManager
 
class  ServicePublication
 Manages an advertised service. More...
 
class  ServiceServer
 Manages an service advertisement. More...
 
class  ServiceServerLink
 Handles a connection to a service. If it's a non-persistent client, automatically disconnects when its first service call has finished. More...
 
struct  ServiceSpec
 
struct  ServiceSpecCallParams
 
class  SingleSubscriberPublisher
 Allows publication of a message to a single subscriber. Only available inside subscriber connection callbacks. More...
 
class  SingleThreadedSpinner
 Spinner which runs in a single thread. More...
 
class  Spinner
 Abstract interface for classes which spin on a callback queue. More...
 
class  StatisticsLogger
 This class logs statistics data about a ROS connection and publishs them periodically on a common topic. More...
 
class  SteadyTime
 
class  SteadyTimer
 Manages a steady-clock timer callback. More...
 
struct  SteadyTimerEvent
 Structure passed as a parameter to the callback invoked by a ros::SteadyTimer. More...
 
struct  SteadyTimerOptions
 Encapsulates all options available for starting a timer. More...
 
struct  SubscribeOptions
 Encapsulates all options available for creating a Subscriber. More...
 
class  Subscriber
 Manages an subscription callback on a specific topic. More...
 
struct  SubscriberCallbacks
 
class  SubscriberLink
 
class  Subscription
 Manages a subscription on a single topic. More...
 
class  SubscriptionCallbackHelper
 Abstract base class used by subscriptions to deal with concrete message types through a common interface. This is one part of the roscpp API that is not fully stable, so overloading this class is not recommended. More...
 
struct  SubscriptionCallbackHelperCallParams
 
struct  SubscriptionCallbackHelperDeserializeParams
 
class  SubscriptionCallbackHelperT
 Concrete generic implementation of SubscriptionCallbackHelper for any normal message type. Use directly with care, this is mostly for internal use. More...
 
class  SubscriptionQueue
 
class  Time
 
class  TimeBase
 
class  TimeNotInitializedException
 
class  Timer
 Manages a timer callback. More...
 
struct  TimerEvent
 Structure passed as a parameter to the callback invoked by a ros::Timer. More...
 
class  TimerManager
 
struct  TimerOptions
 Encapsulates all options available for starting a timer. More...
 
class  TopicManager
 
class  Transport
 Abstract base class that allows abstraction of the transport type, eg. TCP, shared memory, UDP... More...
 
class  TransportHints
 Provides a way of specifying network transport hints to ros::NodeHandle::subscribe() and someday ros::NodeHandle::advertise() More...
 
class  TransportPublisherLink
 Handles a connection to a single publisher on a given topic. Receives messages from a publisher and hands them off to its parent Subscription. More...
 
class  TransportSubscriberLink
 SubscriberLink handles broadcasting messages to a single subscriber on a single topic. More...
 
class  TransportTCP
 TCPROS transport. More...
 
class  TransportUDP
 UDPROS transport. More...
 
struct  TransportUDPHeader
 
class  WallDuration
 
class  WallRate
 
class  WallTime
 
class  WallTimer
 Manages a wall-clock timer callback. More...
 
struct  WallTimerEvent
 Structure passed as a parameter to the callback invoked by a ros::WallTimer. More...
 
struct  WallTimerOptions
 Encapsulates all options available for starting a timer. More...
 
class  XMLRPCCallWrapper
 
class  XMLRPCManager
 

Typedefs

typedef boost::shared_ptr< AsyncSpinnerImplAsyncSpinnerImplPtr
 
typedef boost::shared_ptr< ASyncXMLRPCConnectionASyncXMLRPCConnectionPtr
 
typedef boost::shared_ptr< CallbackInterfaceCallbackInterfacePtr
 
typedef boost::shared_ptr< CallbackQueueCallbackQueuePtr
 
typedef boost::shared_ptr< ConnectionManagerConnectionManagerPtr
 
typedef boost::shared_ptr< ConnectionConnectionPtr
 
typedef boost::function< bool(const ConnectionPtr &, const Header &)> HeaderReceivedFunc
 
typedef init_options::InitOption InitOption
 
typedef TimerManager< SteadyTime, WallDuration, SteadyTimerEventInternalTimerManager
 
typedef boost::shared_ptr< InternalTimerManagerInternalTimerManagerPtr
 
typedef boost::shared_ptr< IntraProcessPublisherLinkIntraProcessPublisherLinkPtr
 
typedef boost::shared_ptr< IntraProcessSubscriberLinkIntraProcessSubscriberLinkPtr
 
typedef std::list< ServicePublicationPtrL_ServicePublication
 
typedef std::list< ServiceServerLinkPtrL_ServiceServerLink
 
typedef std::list< SubscriptionPtrL_Subscription
 
typedef std::map< std::string, std::string > M_string
 
typedef std::map< std::string, std::string > M_string
 
typedef boost::shared_ptr< M_stringM_stringPtr
 
typedef boost::shared_ptr< MessageDeserializerMessageDeserializerPtr
 
typedef boost::shared_ptr< NodeHandleNodeHandlePtr
 
typedef boost::shared_ptr< std::vector< socket_pollfd > > pollfd_vector_ptr
 
typedef boost::shared_ptr< PollManagerPollManagerPtr
 
typedef boost::shared_ptr< PublicationPublicationPtr
 
typedef boost::weak_ptr< PublicationPublicationWPtr
 
typedef boost::shared_ptr< PublisherLinkPublisherLinkPtr
 
typedef boost::function< void(const ConnectionPtr &, const boost::shared_array< uint8_t > &, uint32_t, bool)> ReadFinishedFunc
 
typedef std::set< ASyncXMLRPCConnectionPtrS_ASyncXMLRPCConnection
 
typedef std::set< ConnectionPtrS_Connection
 
typedef std::set< std::string > S_string
 
typedef std::set< SubscriptionPtrS_Subscription
 
typedef boost::shared_ptr< ServiceCallbackHelperServiceCallbackHelperPtr
 
typedef boost::shared_ptr< ServiceClientLinkServiceClientLinkPtr
 
typedef boost::shared_ptr< ServiceClientServiceClientPtr
 
typedef boost::shared_ptr< ServiceManagerServiceManagerPtr
 
typedef boost::shared_ptr< ServicePublicationServicePublicationPtr
 
typedef boost::weak_ptr< ServicePublicationServicePublicationWPtr
 
typedef boost::shared_ptr< ServiceServerLinkServiceServerLinkPtr
 
typedef int signal_fd_t
 
typedef int socket_fd_t
 
typedef struct pollfd socket_pollfd
 
typedef boost::function< void(const SteadyTimerEvent &)> SteadyTimerCallback
 
typedef std::pair< std::string, std::string > StringPair
 
typedef boost::shared_ptr< SubscriberCallbacksSubscriberCallbacksPtr
 
typedef boost::shared_ptr< SubscriberLinkSubscriberLinkPtr
 
typedef boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
 
typedef boost::shared_ptr< SubscriptionCallbackHelperSubscriptionCallbackHelperPtr
 
typedef boost::shared_ptr< SubscriptionCallback > SubscriptionCallbackPtr
 
typedef boost::shared_ptr< SubscriptionSubscriptionPtr
 
typedef boost::shared_ptr< SubscriptionQueueSubscriptionQueuePtr
 
typedef boost::weak_ptr< SubscriptionSubscriptionWPtr
 
typedef boost::function< void(const TimerEvent &)> TimerCallback
 
typedef boost::shared_ptr< TopicManagerTopicManagerPtr
 
typedef boost::shared_ptr< TransportTransportPtr
 
typedef boost::shared_ptr< TransportPublisherLinkTransportPublisherLinkPtr
 
typedef boost::shared_ptr< TransportSubscriberLinkTransportSubscriberLinkPtr
 
typedef boost::shared_ptr< TransportTCPTransportTCPPtr
 
typedef struct ros::TransportUDPHeader TransportUDPHeader
 
typedef boost::shared_ptr< TransportUDPTransportUDPPtr
 
typedef std::vector< ConnectionPtrV_Connection
 
typedef std::vector< PublicationPtrV_Publication
 
typedef std::vector< PublisherV_Publisher
 
typedef std::vector< PublisherLinkPtrV_PublisherLink
 
typedef std::vector< ServiceClientLinkPtrV_ServiceClientLink
 
typedef std::vector< ServicePublicationPtrV_ServicePublication
 
typedef std::vector< ServiceServerV_ServiceServer
 
typedef std::vector< std::string > V_string
 
typedef std::vector< SubscriberV_Subscriber
 
typedef std::vector< SubscriberLinkPtrV_SubscriberLink
 
typedef std::vector< SubscriptionPtrV_Subscription
 
typedef boost::shared_ptr< void const > VoidConstPtr
 
typedef boost::weak_ptr< void const > VoidConstWPtr
 
typedef boost::function< void(void)> VoidFunc
 
typedef boost::shared_ptr< void > VoidPtr
 
typedef boost::signals2::signal< void(void)> VoidSignal
 
typedef boost::weak_ptr< void > VoidWPtr
 
typedef std::vector< std::pair< std::string, std::string > > VP_string
 
typedef boost::function< void(const WallTimerEvent &)> WallTimerCallback
 
typedef boost::function< void(const ConnectionPtr &)> WriteFinishedFunc
 
typedef boost::shared_ptr< XMLRPCCallWrapperXMLRPCCallWrapperPtr
 
typedef boost::function< void(XmlRpc::XmlRpcValue &, XmlRpc::XmlRpcValue &)> XMLRPCFunc
 
typedef boost::shared_ptr< XMLRPCManagerXMLRPCManagerPtr
 

Functions

ROSCPP_DECL void add_socket_to_watcher (int epfd, int fd)
 
void atexitCallback ()
 
void basicSigintHandler (int sig)
 
void check_ipv6_environment ()
 
void checkForShutdown ()
 
void clockCallback (const rosgraph_msgs::Clock::ConstPtr &msg)
 
void close_signal_pair (signal_fd_t signal_pair[2])
 
ROSCPP_DECL int close_socket (socket_fd_t &socket)
 Close the socket. More...
 
ROSCPP_DECL void close_socket_watcher (int fd)
 
bool closeAllConnections (roscpp::Empty::Request &, roscpp::Empty::Response &)
 
void closeTransport (const TransportUDPPtr &trans)
 
ROSCPP_DECL int create_signal_pair (signal_fd_t signal_pair[2])
 
ROSCPP_DECL int create_socket_watcher ()
 
ROS_DEPRECATED boost::shared_ptr< M > defaultMessageCreateFunction ()
 
template<typename M >
boost::shared_ptr< M > defaultServiceCreateFunction ()
 
ROSCPP_DECL void del_socket_from_watcher (int epfd, int fd)
 
const Duration DURATION_MAX (std::numeric_limits< int32_t >::max(), 999999999)
 
const Duration DURATION_MIN (std::numeric_limits< int32_t >::min(), 0)
 
static bool g_initialized (false)
 
static bool g_stopped (false)
 
static bool g_use_sim_time (true)
 
bool get_environment_variable (std::string &str, const char *environment_variable)
 
const ROSCPP_DECL std::string & getDefaultMasterURI ()
 returns the default master uri that is used if no other is specified, e.g. by defining ROS_MASTER_URI. More...
 
ROSCPP_DECL CallbackQueuegetGlobalCallbackQueue ()
 Returns a pointer to the global default callback queue. More...
 
CallbackQueuePtr getInternalCallbackQueue ()
 
ROSCPP_DECL InternalTimerManagerPtr getInternalTimerManager ()
 
bool getLoggers (roscpp::GetLoggers::Request &, roscpp::GetLoggers::Response &resp)
 
void getPid (const XmlRpcValue &params, XmlRpcValue &result)
 
ROSCPP_DECL std::string getROSArg (int argc, const char *const *argv, const std::string &arg)
 searches the command line arguments for the given arg parameter. In case this argument is not found an empty string is returned. More...
 
ROSCPP_DECL void init (const M_string &remappings, const std::string &name, uint32_t options=0)
 alternate ROS initialization function. More...
 
ROSCPP_DECL void init (const VP_string &remapping_args, const std::string &name, uint32_t options=0)
 alternate ROS initialization function. More...
 
ROSCPP_DECL void init (int &argc, char **argv, const std::string &name, uint32_t options=0)
 ROS initialization function. More...
 
ROSCPP_DECL void initInternalTimerManager ()
 
void internalCallbackQueueThreadFunc ()
 
ROSCPP_DECL int is_async_connected (socket_fd_t &socket, int &err)
 
ROSCPP_DECL bool isInitialized ()
 Returns whether or not ros::init() has been called. More...
 
ROSCPP_DECL bool isShuttingDown ()
 Returns whether or not ros::shutdown() has been (or is being) called. More...
 
ROSCPP_DECL bool isStarted ()
 Returns whether or not the node has been started through ros::start() More...
 
ROSCPP_DECL int last_socket_error ()
 
ROSCPP_DECL bool last_socket_error_is_would_block ()
 
const ROSCPP_DECL char * last_socket_error_string ()
 
bool md5sumsMatch (const std::string &lhs, const std::string &rhs)
 
ROSTIME_DECL void normalizeSecNSec (uint32_t &sec, uint32_t &nsec)
 
ROSTIME_DECL void normalizeSecNSec (uint64_t &sec, uint64_t &nsec)
 
ROSTIME_DECL void normalizeSecNSecSigned (int32_t &sec, int32_t &nsec)
 
ROSTIME_DECL void normalizeSecNSecSigned (int64_t &sec, int64_t &nsec)
 
ROSTIME_DECL void normalizeSecNSecUnsigned (int64_t &sec, int64_t &nsec)
 
ROSCPP_DECL bool ok ()
 Check whether it's time to exit. More...
 
ROSTIME_DECL std::ostream & operator<< (std::ostream &os, const Duration &rhs)
 
ROSTIME_DECL std::ostream & operator<< (std::ostream &os, const SteadyTime &rhs)
 
ROSTIME_DECL std::ostream & operator<< (std::ostream &os, const Time &rhs)
 
ROSTIME_DECL std::ostream & operator<< (std::ostream &os, const WallDuration &rhs)
 
ROSTIME_DECL std::ostream & operator<< (std::ostream &os, const WallTime &rhs)
 
ROSCPP_DECL pollfd_vector_ptr poll_sockets (int epfd, socket_pollfd *fds, nfds_t nfds, int timeout)
 A cross platform polling function for sockets. More...
 
ssize_t read_signal (const signal_fd_t &signal, void *buffer, const size_t &nbyte)
 
ROSCPP_DECL void removeROSArgs (int argc, const char *const *argv, V_string &args_out)
 returns a vector of program arguments that do not include any ROS remapping arguments. Useful if you need to parse your arguments to determine your node name More...
 
ROSCPP_DECL void requestShutdown ()
 Request that the node shut itself down from within a ROS thread. More...
 
int ros_nanosleep (const uint32_t &sec, const uint32_t &nsec)
 
ROSTIME_DECL void ros_steadytime (uint32_t &sec, uint32_t &nsec)
 
bool ros_wallsleep (uint32_t sec, uint32_t nsec)
 
ROSTIME_DECL void ros_walltime (uint32_t &sec, uint32_t &nsec)
 
ROSCPP_DECL void set_events_on_socket (int epfd, int fd, int events)
 
ROSCPP_DECL int set_non_blocking (socket_fd_t &socket)
 
bool setLoggerLevel (roscpp::SetLoggerLevel::Request &req, roscpp::SetLoggerLevel::Response &)
 
ROSCPP_DECL void shutdown ()
 Disconnects everything and unregisters from the master. It is generally not necessary to call this function, as the node will automatically shutdown when all NodeHandles destruct. However, if you want to break out of a spin() loop explicitly, this function allows that. More...
 
void shutdownCallback (XmlRpc::XmlRpcValue &params, XmlRpc::XmlRpcValue &result)
 
const ROSCPP_DECL char * socket_error_string (int err)
 
ROSCPP_DECL void spin ()
 Enter simple event loop. More...
 
ROSCPP_DECL void spin (Spinner &spinner)
 Enter simple event loop. More...
 
ROSCPP_DECL void spinOnce ()
 Process a single round of callbacks. More...
 
void spinThread ()
 
ROSCPP_DECL void start ()
 Actually starts the internals of the node (spins up threads, starts the network polling and xmlrpc loops, connects to internal subscriptions like /clock, starts internal service servers, etc.). More...
 
const Time TIME_MAX (std::numeric_limits< uint32_t >::max(), 999999999)
 
bool urisEqual (const std::string &uri1, const std::string &uri2)
 
ROSCPP_DECL void waitForShutdown ()
 Wait for this node to be shutdown, whether through Ctrl-C, ros::shutdown(), or similar. More...
 
ssize_t write_signal (const signal_fd_t &signal, const void *buffer, const size_t &nbyte)
 

Variables

const ROSTIME_DECL Duration DURATION_MAX
 
const ROSTIME_DECL Duration DURATION_MIN
 
static bool g_atexit_registered = false
 
CallbackQueuePtr g_global_queue
 
static uint32_t g_init_options = 0
 
static bool g_initialized = false
 
static CallbackQueuePtr g_internal_callback_queue
 
static boost::thread g_internal_queue_thread
 
int32_t g_nh_refcount = 0
 
boost::mutex g_nh_refcount_mutex
 
bool g_node_started_by_nh = false
 
static bool g_ok = false
 
ROSOutAppenderg_rosout_appender
 
static bool g_shutdown_registered = false
 
static bool g_shutdown_requested = false
 
static volatile bool g_shutting_down = false
 
static boost::recursive_mutex g_shutting_down_mutex
 
static Time g_sim_time (0, 0)
 
static boost::mutex g_sim_time_mutex
 
static boost::mutex g_start_mutex
 
static bool g_started = false
 
static InternalTimerManagerPtr g_timer_manager
 
const ROSTIME_DECL Time TIME_MAX
 
const ROSTIME_DECL Time TIME_MIN
 
const Time TIME_MIN (0, 1)
 

Detailed Description

Todo:
Locking can be significantly simplified here once the Node API goes away.

Typedef Documentation

◆ AsyncSpinnerImplPtr

Definition at line 82 of file spinner.h.

◆ ASyncXMLRPCConnectionPtr

Definition at line 70 of file xmlrpc_manager.h.

◆ CallbackInterfacePtr

Definition at line 74 of file callback_queue_interface.h.

◆ CallbackQueuePtr

Definition at line 185 of file callback_queue.h.

◆ ConnectionManagerPtr

Definition at line 41 of file connection_manager.h.

◆ ConnectionPtr

Definition at line 57 of file connection.h.

◆ HeaderReceivedFunc

typedef boost::function<bool(const ConnectionPtr&, const Header&)> ros::HeaderReceivedFunc

Definition at line 62 of file connection.h.

◆ InitOption

Definition at line 66 of file init.h.

◆ InternalTimerManager

Definition at line 38 of file internal_timer_manager.h.

◆ InternalTimerManagerPtr

Definition at line 40 of file internal_timer_manager.h.

◆ IntraProcessPublisherLinkPtr

Definition at line 73 of file intraprocess_publisher_link.h.

◆ IntraProcessSubscriberLinkPtr

Definition at line 42 of file intraprocess_publisher_link.h.

◆ L_ServicePublication

Definition at line 83 of file forwards.h.

◆ L_ServiceServerLink

Definition at line 87 of file forwards.h.

◆ L_Subscription

Definition at line 75 of file forwards.h.

◆ M_string

typedef std::map<std::string, std::string> ros::M_string

Definition at line 47 of file message.h.

◆ MessageDeserializerPtr

Definition at line 61 of file message_deserializer.h.

◆ NodeHandlePtr

Definition at line 90 of file forwards.h.

◆ pollfd_vector_ptr

Definition at line 143 of file io.h.

◆ PollManagerPtr

Definition at line 38 of file connection_manager.h.

◆ PublicationPtr

Definition at line 66 of file forwards.h.

◆ PublicationWPtr

typedef boost::weak_ptr< Publication > ros::PublicationWPtr

Definition at line 57 of file rosout_appender.h.

◆ PublisherLinkPtr

Definition at line 78 of file forwards.h.

◆ ReadFinishedFunc

typedef boost::function<void(const ConnectionPtr&, const boost::shared_array<uint8_t>&, uint32_t, bool)> ros::ReadFinishedFunc

Definition at line 59 of file connection.h.

◆ S_ASyncXMLRPCConnection

Definition at line 71 of file xmlrpc_manager.h.

◆ S_Connection

typedef std::set<ConnectionPtr> ros::S_Connection

Definition at line 64 of file forwards.h.

◆ S_Subscription

Definition at line 77 of file forwards.h.

◆ ServiceCallbackHelperPtr

Definition at line 140 of file service_callback_helper.h.

◆ ServiceClientLinkPtr

Definition at line 84 of file service_client_link.h.

◆ ServiceClientPtr

Definition at line 212 of file service_client.h.

◆ ServiceManagerPtr

Definition at line 189 of file forwards.h.

◆ ServicePublicationPtr

Definition at line 81 of file forwards.h.

◆ ServicePublicationWPtr

Definition at line 43 of file service_client_link.h.

◆ ServiceServerLinkPtr

Definition at line 85 of file forwards.h.

◆ signal_fd_t

typedef int ros::signal_fd_t

Definition at line 139 of file io.h.

◆ socket_fd_t

typedef int ros::socket_fd_t

Definition at line 138 of file io.h.

◆ socket_pollfd

typedef struct pollfd ros::socket_pollfd

Definition at line 140 of file io.h.

◆ SteadyTimerCallback

typedef boost::function<void(const SteadyTimerEvent&)> ros::SteadyTimerCallback

Definition at line 187 of file forwards.h.

◆ SubscriberCallbacksPtr

Definition at line 127 of file forwards.h.

◆ SubscriberLinkPtr

Definition at line 69 of file forwards.h.

◆ SubscriberStatusCallback

typedef boost::function<void(const SingleSubscriberPublisher&)> ros::SubscriberStatusCallback

Definition at line 94 of file forwards.h.

◆ SubscriptionCallbackHelperPtr

Definition at line 42 of file message_deserializer.h.

◆ SubscriptionCallbackPtr

typedef boost::shared_ptr<SubscriptionCallback> ros::SubscriptionCallbackPtr

Definition at line 50 of file subscription.h.

◆ SubscriptionPtr

Definition at line 72 of file forwards.h.

◆ SubscriptionQueuePtr

Definition at line 53 of file subscription.h.

◆ SubscriptionWPtr

typedef boost::weak_ptr< Subscription > ros::SubscriptionWPtr

Definition at line 74 of file forwards.h.

◆ TimerCallback

typedef boost::function<void(const TimerEvent&)> ros::TimerCallback

Definition at line 147 of file forwards.h.

◆ TopicManagerPtr

Definition at line 191 of file forwards.h.

◆ TransportPtr

Definition at line 55 of file connection.h.

◆ TransportPublisherLinkPtr

Definition at line 92 of file transport_publisher_link.h.

◆ TransportSubscriberLinkPtr

Definition at line 75 of file transport_subscriber_link.h.

◆ TransportTCPPtr

Definition at line 58 of file forwards.h.

◆ TransportUDPHeader

◆ TransportUDPPtr

Definition at line 60 of file forwards.h.

◆ V_Connection

typedef std::vector<ConnectionPtr> ros::V_Connection

Definition at line 65 of file forwards.h.

◆ V_Publication

typedef std::vector<PublicationPtr> ros::V_Publication

Definition at line 68 of file forwards.h.

◆ V_Publisher

typedef std::vector<Publisher> ros::V_Publisher

Definition at line 215 of file publisher.h.

◆ V_PublisherLink

typedef std::vector<PublisherLinkPtr> ros::V_PublisherLink

Definition at line 80 of file forwards.h.

◆ V_ServiceClientLink

Definition at line 50 of file service_publication.h.

◆ V_ServicePublication

Definition at line 84 of file forwards.h.

◆ V_ServiceServer

typedef std::vector<ServiceServer> ros::V_ServiceServer

Definition at line 107 of file service_server.h.

◆ V_Subscriber

typedef std::vector<Subscriber> ros::V_Subscriber

Definition at line 116 of file subscriber.h.

◆ V_SubscriberLink

typedef std::vector< SubscriberLinkPtr > ros::V_SubscriberLink

Definition at line 71 of file forwards.h.

◆ V_Subscription

typedef std::vector<SubscriptionPtr> ros::V_Subscription

Definition at line 76 of file forwards.h.

◆ VoidConstPtr

typedef boost::shared_ptr<void const> ros::VoidConstPtr

Definition at line 52 of file forwards.h.

◆ VoidConstWPtr

typedef boost::weak_ptr<void const> ros::VoidConstWPtr

Definition at line 53 of file forwards.h.

◆ VoidFunc

typedef boost::function<void(void)> ros::VoidFunc

Definition at line 46 of file poll_manager.h.

◆ VoidPtr

Definition at line 50 of file forwards.h.

◆ VoidSignal

typedef boost::signals2::signal<void(void)> ros::VoidSignal

Definition at line 45 of file poll_manager.h.

◆ VoidWPtr

typedef boost::weak_ptr<void> ros::VoidWPtr

Definition at line 51 of file forwards.h.

◆ WallTimerCallback

typedef boost::function<void(const WallTimerEvent&)> ros::WallTimerCallback

Definition at line 167 of file forwards.h.

◆ WriteFinishedFunc

typedef boost::function<void(const ConnectionPtr&)> ros::WriteFinishedFunc

Definition at line 60 of file connection.h.

◆ XMLRPCCallWrapperPtr

Definition at line 57 of file xmlrpc_manager.h.

◆ XMLRPCFunc

typedef boost::function<void(XmlRpc::XmlRpcValue&, XmlRpc::XmlRpcValue&)> ros::XMLRPCFunc

Definition at line 92 of file xmlrpc_manager.h.

◆ XMLRPCManagerPtr

Definition at line 195 of file forwards.h.

Function Documentation

◆ add_socket_to_watcher()

void ros::add_socket_to_watcher ( int  epfd,
int  fd 
)

Definition at line 131 of file io.cpp.

◆ atexitCallback()

void ros::atexitCallback ( )

Definition at line 147 of file init.cpp.

◆ basicSigintHandler()

void ros::basicSigintHandler ( int  sig)

Definition at line 271 of file init.cpp.

◆ check_ipv6_environment()

void ros::check_ipv6_environment ( )

Definition at line 439 of file init.cpp.

◆ checkForShutdown()

void ros::checkForShutdown ( )

Definition at line 121 of file init.cpp.

◆ clockCallback()

void ros::clockCallback ( const rosgraph_msgs::Clock::ConstPtr &  msg)

Definition at line 256 of file init.cpp.

◆ close_signal_pair()

void ros::close_signal_pair ( signal_fd_t  signal_pair[2])
inline

Closes the signal pair - on windows we're using sockets (because windows select() function cant handle pipes). On linux, we're just using the pipes.

Parameters
signal_pair: the signal pair type.

Definition at line 174 of file io.h.

◆ close_socket()

int ros::close_socket ( socket_fd_t socket)

Close the socket.

Returns
int : 0 on success, -1 on failure.

Definition at line 524 of file io.cpp.

◆ close_socket_watcher()

void ros::close_socket_watcher ( int  fd)

Definition at line 126 of file io.cpp.

◆ closeAllConnections()

bool ros::closeAllConnections ( roscpp::Empty::Request &  ,
roscpp::Empty::Response &   
)

Definition at line 249 of file init.cpp.

◆ closeTransport()

void ros::closeTransport ( const TransportUDPPtr trans)

Definition at line 448 of file subscription.cpp.

◆ create_signal_pair()

int ros::create_signal_pair ( signal_fd_t  signal_pair[2])

This code is primarily from the msdn socket tutorials.

Parameters
signal_pair: a pair of sockets linked to each other over localhost.
Returns
0 on success, -1 on failure.

Definition at line 548 of file io.cpp.

◆ create_socket_watcher()

int ros::create_socket_watcher ( )

Definition at line 114 of file io.cpp.

◆ defaultServiceCreateFunction()

template<typename M >
boost::shared_ptr<M> ros::defaultServiceCreateFunction ( )
inline

Definition at line 51 of file service_callback_helper.h.

◆ del_socket_from_watcher()

void ros::del_socket_from_watcher ( int  epfd,
int  fd 
)

Definition at line 149 of file io.cpp.

◆ getDefaultMasterURI()

const std::string & ros::getDefaultMasterURI ( )

returns the default master uri that is used if no other is specified, e.g. by defining ROS_MASTER_URI.

Definition at line 640 of file init.cpp.

◆ getGlobalCallbackQueue()

CallbackQueue * ros::getGlobalCallbackQueue ( )

Returns a pointer to the global default callback queue.

This is the queue that all callbacks get added to unless a different one is specified, either in the NodeHandle or in the individual NodeHandle::subscribe()/NodeHandle::advertise()/etc. functions.

Definition at line 595 of file init.cpp.

◆ getInternalCallbackQueue()

CallbackQueuePtr ros::getInternalCallbackQueue ( )

Definition at line 261 of file init.cpp.

◆ getInternalTimerManager()

InternalTimerManagerPtr ros::getInternalTimerManager ( )

Definition at line 36 of file internal_timer_manager.cpp.

◆ getLoggers()

bool ros::getLoggers ( roscpp::GetLoggers::Request &  ,
roscpp::GetLoggers::Response &  resp 
)

Definition at line 173 of file init.cpp.

◆ getPid()

void ros::getPid ( const XmlRpcValue params,
XmlRpcValue result 
)

Definition at line 90 of file xmlrpc_manager.cpp.

◆ getROSArg()

std::string ros::getROSArg ( int  argc,
const char *const *  argv,
const std::string &  arg 
)

searches the command line arguments for the given arg parameter. In case this argument is not found an empty string is returned.

Parameters
argcthe number of command-line arguments
argvthe command-line arguments
argargument to search for

Definition at line 544 of file init.cpp.

◆ init() [1/3]

void ros::init ( const M_string remappings,
const std::string &  name,
uint32_t  options = 0 
)

alternate ROS initialization function.

Parameters
remappingsA map<string, string> where each one constitutes a name remapping, or one of the special remappings like __name, __master, __ns, etc.
nameName of this node. The name must be a base name, ie. it cannot contain namespaces.
options[optional] Options to start the node with (a set of bit flags from ros::init_options)
Exceptions
InvalidNodeNameExceptionIf the name passed in is not a valid "base" name

Definition at line 459 of file init.cpp.

◆ init() [2/3]

void ros::init ( const VP_string remapping_args,
const std::string &  name,
uint32_t  options = 0 
)

alternate ROS initialization function.

Parameters
remappingsA vector<pair<string, string> > where each one constitutes a name remapping, or one of the special remappings like __name, __master, __ns, etc.
nameName of this node. The name must be a base name, ie. it cannot contain namespaces.
options[optional] Options to start the node with (a set of bit flags from ros::init_options)
Exceptions
InvalidNodeNameExceptionIf the name passed in is not a valid "base" name

Definition at line 531 of file init.cpp.

◆ init() [3/3]

void ros::init ( int &  argc,
char **  argv,
const std::string &  name,
uint32_t  options = 0 
)

ROS initialization function.

This function will parse any ROS arguments (e.g., topic name remappings), and will consume them (i.e., argc and argv may be modified as a result of this call).

Use this version if you are using the NodeHandle API

Parameters
argc
argv
nameName of this node. The name must be a base name, ie. it cannot contain namespaces.
options[optional] Options to start the node with (a set of bit flags from ros::init_options)
Exceptions
InvalidNodeNameExceptionIf the name passed in is not a valid "base" name

Definition at line 497 of file init.cpp.

◆ initInternalTimerManager()

void ros::initInternalTimerManager ( )

Definition at line 41 of file internal_timer_manager.cpp.

◆ internalCallbackQueueThreadFunc()

void ros::internalCallbackQueueThreadFunc ( )

Definition at line 277 of file init.cpp.

◆ is_async_connected()

int ros::is_async_connected ( socket_fd_t socket,
int &  err 
)

Checks if the async socket connection is success, failure or connecting.

Parameters
err- WSAGetLastError()/errno on failure.
Returns
int : 1 on connected, 0 on connecting, -1 on failure.

Definition at line 384 of file io.cpp.

◆ isInitialized()

bool ros::isInitialized ( )

Returns whether or not ros::init() has been called.

Definition at line 111 of file init.cpp.

◆ isShuttingDown()

bool ros::isShuttingDown ( )

Returns whether or not ros::shutdown() has been (or is being) called.

Definition at line 116 of file init.cpp.

◆ isStarted()

bool ros::isStarted ( )

Returns whether or not the node has been started through ros::start()

Definition at line 289 of file init.cpp.

◆ last_socket_error()

int ros::last_socket_error ( )

Definition at line 70 of file io.cpp.

◆ last_socket_error_is_would_block()

bool ros::last_socket_error_is_would_block ( )

Definition at line 98 of file io.cpp.

◆ last_socket_error_string()

const char * ros::last_socket_error_string ( )

Definition at line 90 of file io.cpp.

◆ md5sumsMatch()

bool ros::md5sumsMatch ( const std::string &  lhs,
const std::string &  rhs 
)

Definition at line 193 of file topic_manager.cpp.

◆ ok()

bool ros::ok ( )

Check whether it's time to exit.

ok() becomes false once ros::shutdown() has been called and is finished

Returns
true if we're still OK, false if it's time to exit

Definition at line 600 of file init.cpp.

◆ poll_sockets()

pollfd_vector_ptr ros::poll_sockets ( int  epfd,
socket_pollfd fds,
nfds_t  nfds,
int  timeout 
)

A cross platform polling function for sockets.

Windows doesn't have a polling function until Vista (WSAPoll) and even then its implementation is not supposed to be great. This works for a broader range of platforms and will suffice.

Parameters
epfd- the socket watcher to poll on.
fds- the socket set (descriptor's and events) to poll for.
nfds- the number of descriptors to poll for.
timeout- timeout in milliseconds.
Returns
pollfd_vector_ptr : NULL on error, empty on timeout, a list of structures with received events.

Definition at line 196 of file io.cpp.

◆ read_signal()

ssize_t ros::read_signal ( const signal_fd_t signal,
void *  buffer,
const size_t &  nbyte 
)
inline

Read from a signal_fd_t device. On windows we're using sockets (because windows select() function cant handle pipes) so we have to use socket functions. On linux, we're just using the pipes.

Definition at line 212 of file io.h.

◆ removeROSArgs()

void ros::removeROSArgs ( int  argc,
const char *const *  argv,
V_string args_out 
)

returns a vector of program arguments that do not include any ROS remapping arguments. Useful if you need to parse your arguments to determine your node name

Parameters
argcthe number of command-line arguments
argvthe command-line arguments
[out]args_outOutput args, stripped of any ROS args

Definition at line 558 of file init.cpp.

◆ requestShutdown()

void ros::requestShutdown ( )

Request that the node shut itself down from within a ROS thread.

This method signals a ROS thread to call shutdown().

Definition at line 142 of file init.cpp.

◆ set_events_on_socket()

void ros::set_events_on_socket ( int  epfd,
int  fd,
int  events 
)

Definition at line 161 of file io.cpp.

◆ set_non_blocking()

int ros::set_non_blocking ( socket_fd_t socket)

Sets the socket as non blocking.

Returns
int : 0 on success, WSAGetLastError()/errno on failure.

Definition at line 503 of file io.cpp.

◆ setLoggerLevel()

bool ros::setLoggerLevel ( roscpp::SetLoggerLevel::Request &  req,
roscpp::SetLoggerLevel::Response &   
)

Definition at line 210 of file init.cpp.

◆ shutdown()

void ros::shutdown ( )

Disconnects everything and unregisters from the master. It is generally not necessary to call this function, as the node will automatically shutdown when all NodeHandles destruct. However, if you want to break out of a spin() loop explicitly, this function allows that.

Definition at line 605 of file init.cpp.

◆ shutdownCallback()

void ros::shutdownCallback ( XmlRpc::XmlRpcValue params,
XmlRpc::XmlRpcValue result 
)

Definition at line 157 of file init.cpp.

◆ socket_error_string()

const char * ros::socket_error_string ( int  err)

Definition at line 78 of file io.cpp.

◆ spin() [1/2]

void ros::spin ( )

Enter simple event loop.

This method enters a loop, processing callbacks. This method should only be used if the NodeHandle API is being used.

This method is mostly useful when your node does all of its work in subscription callbacks. It will not process any callbacks that have been assigned to custom queues.

Definition at line 571 of file init.cpp.

◆ spin() [2/2]

void ros::spin ( Spinner spinner)

Enter simple event loop.

This method enters a loop, processing callbacks. This method should only be used if the NodeHandle API is being used.

This method is mostly useful when your node does all of its work in subscription callbacks. It will not process any callbacks that have been assigned to custom queues.

Parameters
spinnera spinner to use to call callbacks. Two default implementations are available, SingleThreadedSpinner and MultiThreadedSpinner

Definition at line 577 of file init.cpp.

◆ spinOnce()

void ros::spinOnce ( )

Process a single round of callbacks.

This method is useful if you have your own loop running and would like to process any callbacks that are available. This is equivalent to calling callAvailable() on the global CallbackQueue. It will not process any callbacks that have been assigned to custom queues.

Definition at line 582 of file init.cpp.

◆ spinThread()

void ros::spinThread ( )

Definition at line 147 of file node_handle.cpp.

◆ start()

void ros::start ( )

Actually starts the internals of the node (spins up threads, starts the network polling and xmlrpc loops, connects to internal subscriptions like /clock, starts internal service servers, etc.).

Usually unnecessary to call manually, as it is automatically called by the creation of the first NodeHandle if the node has not already been started. If you would like to prevent the automatic shutdown caused by the last NodeHandle going out of scope, call this before any NodeHandle has been created (e.g. immediately after init())

Definition at line 294 of file init.cpp.

◆ urisEqual()

bool ros::urisEqual ( const std::string &  uri1,
const std::string &  uri2 
)

Definition at line 208 of file subscription.cpp.

◆ waitForShutdown()

void ros::waitForShutdown ( )

Wait for this node to be shutdown, whether through Ctrl-C, ros::shutdown(), or similar.

Definition at line 587 of file init.cpp.

◆ write_signal()

ssize_t ros::write_signal ( const signal_fd_t signal,
const void *  buffer,
const size_t &  nbyte 
)
inline

Write to a signal_fd_t device. On windows we're using sockets (because windows select() function cant handle pipes) so we have to use socket functions. On linux, we're just using the pipes.

Definition at line 195 of file io.h.

Variable Documentation

◆ g_atexit_registered

bool ros::g_atexit_registered = false
static

Definition at line 101 of file init.cpp.

◆ g_global_queue

CallbackQueuePtr ros::g_global_queue

Definition at line 95 of file init.cpp.

◆ g_init_options

uint32_t ros::g_init_options = 0
static

Definition at line 105 of file init.cpp.

◆ g_initialized

bool ros::g_initialized = false
static

Definition at line 99 of file init.cpp.

◆ g_internal_callback_queue

CallbackQueuePtr ros::g_internal_callback_queue
static

Definition at line 97 of file init.cpp.

◆ g_internal_queue_thread

boost::thread ros::g_internal_queue_thread
static

Definition at line 109 of file init.cpp.

◆ g_nh_refcount

int32_t ros::g_nh_refcount = 0

Definition at line 55 of file node_handle.cpp.

◆ g_nh_refcount_mutex

boost::mutex ros::g_nh_refcount_mutex

Definition at line 54 of file node_handle.cpp.

◆ g_node_started_by_nh

bool ros::g_node_started_by_nh = false

Definition at line 56 of file node_handle.cpp.

◆ g_ok

bool ros::g_ok = false
static

Definition at line 104 of file init.cpp.

◆ g_rosout_appender

ROSOutAppender* ros::g_rosout_appender

Definition at line 96 of file init.cpp.

◆ g_shutdown_registered

bool ros::g_shutdown_registered = false
static

Definition at line 102 of file init.cpp.

◆ g_shutdown_requested

bool ros::g_shutdown_requested = false
static

Definition at line 106 of file init.cpp.

◆ g_shutting_down

volatile bool ros::g_shutting_down = false
static

Definition at line 107 of file init.cpp.

◆ g_shutting_down_mutex

boost::recursive_mutex ros::g_shutting_down_mutex
static

Definition at line 108 of file init.cpp.

◆ g_start_mutex

boost::mutex ros::g_start_mutex
static

Definition at line 103 of file init.cpp.

◆ g_started

bool ros::g_started = false
static

Definition at line 100 of file init.cpp.

◆ g_timer_manager

InternalTimerManagerPtr ros::g_timer_manager
static

Definition at line 34 of file internal_timer_manager.cpp.



roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas , Jacob Perron
autogenerated on Thu Nov 23 2023 04:01:44