Namespaces | |
namespace | file_log |
internal | |
namespace | init_options |
namespace | master |
Contains functions which allow you to query information about the master. | |
namespace | message_operations |
namespace | message_traits |
namespace | names |
Contains functions which allow you to manipulate ROS names. | |
namespace | network |
internal | |
namespace | param |
Contains functions which allow you to query the parameter server. | |
namespace | serialization |
namespace | service |
Contains functions for querying information about and calling a service. | |
namespace | service_traits |
namespace | this_node |
Contains functions which provide information about this process' ROS node. | |
namespace | topic |
namespace | 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 | Header |
Provides functionality to parse a connection header and retrieve values from it. More... | |
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 |
Event type for subscriptions, const ros::MessageEvent<M const>& can be used in your callback instead of const boost::shared_ptr<M const>&. More... | |
class | MultiThreadedSpinner |
Spinner which spins in multiple threads. More... | |
class | NodeHandle |
roscpp's interface for creating subscribers, publishers, etc. More... | |
class | NodeHandleBackingCollection |
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 | ROSOutAppender |
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... | |
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 | 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 | 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 < AsyncSpinnerImpl > | AsyncSpinnerImplPtr |
typedef boost::shared_ptr < ASyncXMLRPCConnection > | ASyncXMLRPCConnectionPtr |
typedef boost::shared_ptr < CallbackInterface > | CallbackInterfacePtr |
typedef boost::shared_ptr < CallbackQueue > | CallbackQueuePtr |
typedef boost::shared_ptr < ConnectionManager > | ConnectionManagerPtr |
typedef boost::shared_ptr < Connection > | ConnectionPtr |
typedef boost::function< bool(const ConnectionPtr &, const Header &)> | HeaderReceivedFunc |
typedef init_options::InitOption | InitOption |
typedef TimerManager< WallTime, WallDuration, WallTimerEvent > | InternalTimerManager |
typedef boost::shared_ptr < InternalTimerManager > | InternalTimerManagerPtr |
typedef boost::shared_ptr < IntraProcessPublisherLink > | IntraProcessPublisherLinkPtr |
typedef boost::shared_ptr < IntraProcessSubscriberLink > | IntraProcessSubscriberLinkPtr |
typedef std::list < ServicePublicationPtr > | L_ServicePublication |
typedef std::list < ServiceServerLinkPtr > | L_ServiceServerLink |
typedef std::list < SubscriptionPtr > | L_Subscription |
typedef std::map< std::string, std::string > | M_string |
typedef boost::shared_ptr < M_string > | M_stringPtr |
typedef boost::shared_ptr < MessageDeserializer > | MessageDeserializerPtr |
typedef boost::shared_ptr < NodeHandle > | NodeHandlePtr |
typedef boost::shared_ptr < PollManager > | PollManagerPtr |
typedef boost::shared_ptr < Publication > | PublicationPtr |
typedef boost::weak_ptr < Publication > | PublicationWPtr |
typedef boost::shared_ptr < PublisherLink > | PublisherLinkPtr |
typedef boost::function< void(const ConnectionPtr &, const boost::shared_array< uint8_t > &, uint32_t, bool)> | ReadFinishedFunc |
typedef log4cxx::helpers::ObjectPtrT < ROSOutAppender > | ROSOutAppenderPtr |
typedef std::set < ASyncXMLRPCConnectionPtr > | S_ASyncXMLRPCConnection |
typedef std::set< ConnectionPtr > | S_Connection |
typedef std::set< std::string > | S_string |
typedef std::set< SubscriptionPtr > | S_Subscription |
typedef boost::shared_ptr < ServiceCallbackHelper > | ServiceCallbackHelperPtr |
typedef boost::shared_ptr < ServiceClientLink > | ServiceClientLinkPtr |
typedef boost::shared_ptr < ServiceClient > | ServiceClientPtr |
typedef boost::shared_ptr < ServiceManager > | ServiceManagerPtr |
typedef boost::shared_ptr < ServicePublication > | ServicePublicationPtr |
typedef boost::weak_ptr < ServicePublication > | ServicePublicationWPtr |
typedef boost::shared_ptr < ServiceServerLink > | ServiceServerLinkPtr |
typedef int | signal_fd_t |
typedef int | socket_fd_t |
typedef struct pollfd | socket_pollfd |
typedef std::pair< std::string, std::string > | StringPair |
typedef boost::shared_ptr < SubscriberCallbacks > | SubscriberCallbacksPtr |
typedef boost::shared_ptr < SubscriberLink > | SubscriberLinkPtr |
typedef boost::function< void(const SingleSubscriberPublisher &)> | SubscriberStatusCallback |
typedef boost::shared_ptr < SubscriptionCallbackHelper > | SubscriptionCallbackHelperPtr |
typedef boost::shared_ptr < SubscriptionCallback > | SubscriptionCallbackPtr |
typedef boost::shared_ptr < Subscription > | SubscriptionPtr |
typedef boost::shared_ptr < SubscriptionQueue > | SubscriptionQueuePtr |
typedef boost::weak_ptr < Subscription > | SubscriptionWPtr |
typedef boost::function< void(const TimerEvent &)> | TimerCallback |
typedef boost::shared_ptr < TopicManager > | TopicManagerPtr |
typedef boost::shared_ptr < Transport > | TransportPtr |
typedef boost::shared_ptr < TransportPublisherLink > | TransportPublisherLinkPtr |
typedef boost::shared_ptr < TransportSubscriberLink > | TransportSubscriberLinkPtr |
typedef boost::shared_ptr < TransportTCP > | TransportTCPPtr |
typedef struct ros::TransportUDPHeader | TransportUDPHeader |
typedef boost::shared_ptr < TransportUDP > | TransportUDPPtr |
typedef std::vector < ConnectionPtr > | V_Connection |
typedef std::vector < PublicationPtr > | V_Publication |
typedef std::vector< Publisher > | V_Publisher |
typedef std::vector < PublisherLinkPtr > | V_PublisherLink |
typedef std::vector < ServiceClientLinkPtr > | V_ServiceClientLink |
typedef std::vector < ServicePublicationPtr > | V_ServicePublication |
typedef std::vector < ServiceServer > | V_ServiceServer |
typedef std::vector< std::string > | V_string |
typedef std::vector< Subscriber > | V_Subscriber |
typedef std::vector < SubscriberLinkPtr > | V_SubscriberLink |
typedef std::vector < SubscriptionPtr > | V_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::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 < XMLRPCCallWrapper > | XMLRPCCallWrapperPtr |
typedef boost::function< void(XmlRpc::XmlRpcValue &, XmlRpc::XmlRpcValue &)> | XMLRPCFunc |
typedef boost::shared_ptr < XMLRPCManager > | XMLRPCManagerPtr |
Functions | |
template<typename T > | |
void | assignServiceConnectionHeader (T *, const boost::shared_ptr< M_string > &, typename boost::disable_if< ros::message_traits::IsMessage< T > >::type *_=0) |
template<typename T > | |
void | assignServiceConnectionHeader (T *t, const boost::shared_ptr< M_string > &connection_header, typename boost::enable_if< ros::message_traits::IsMessage< T > >::type *_=0) |
template<typename T > | |
void | assignSubscriptionConnectionHeader (T *t, const boost::shared_ptr< M_string > &connection_header, typename boost::disable_if< ros::message_traits::IsMessage< T > >::type *_=0) |
template<typename T > | |
void | assignSubscriptionConnectionHeader (T *t, const boost::shared_ptr< M_string > &connection_header, typename boost::enable_if< ros::message_traits::IsMessage< T > >::type *_=0) |
void | atexitCallback () |
void | basicSigintHandler (int sig) |
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. | |
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]) |
template<typename M > | |
ROS_DEPRECATED boost::shared_ptr< M > | defaultMessageCreateFunction () |
template<typename M > | |
boost::shared_ptr< M > | defaultServiceCreateFunction () |
void | disableAllSignalsInThisThread () |
ROSCPP_DECL CallbackQueue * | getGlobalCallbackQueue () |
Returns a pointer to the global default callback queue. | |
CallbackQueuePtr | getInternalCallbackQueue () |
ROSCPP_DECL InternalTimerManagerPtr | getInternalTimerManager () |
bool | getLoggers (roscpp::GetLoggers::Request &, roscpp::GetLoggers::Response &resp) |
void | getPid (const XmlRpcValue ¶ms, XmlRpcValue &result) |
ROSCPP_DECL void | init (const VP_string &remapping_args, const std::string &name, uint32_t options=0) |
alternate ROS initialization function. | |
ROSCPP_DECL void | init (const M_string &remappings, const std::string &name, uint32_t options=0) |
alternate ROS initialization function. | |
ROSCPP_DECL void | init (int &argc, char **argv, const std::string &name, uint32_t options=0) |
ROS initialization function. | |
ROSCPP_DECL void | initInternalTimerManager () |
void | internalCallbackQueueThreadFunc () |
ROSCPP_DECL bool | isInitialized () |
Returns whether or not ros::init() has been called. | |
ROSCPP_DECL bool | isShuttingDown () |
Returns whether or not ros::shutdown() has been (or is being) called. | |
ROSCPP_DECL bool | isStarted () |
Returns whether or not the node has been started through ros::start(). | |
ROSCPP_DECL int | last_socket_error () |
ROSCPP_DECL bool | last_socket_error_is_would_block () |
ROSCPP_DECL const char * | last_socket_error_string () |
bool | md5sumsMatch (const std::string &lhs, const std::string &rhs) |
ROSCPP_DECL bool | ok () |
Check whether it's time to exit. | |
ROSCPP_DECL int | poll_sockets (socket_pollfd *fds, nfds_t nfds, int timeout) |
A cross platform polling function for sockets. | |
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 | |
ROSCPP_DECL void | requestShutdown () |
Request that the node shut itself down from within a ROS thread. | |
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. | |
void | shutdownCallback (XmlRpc::XmlRpcValue ¶ms, XmlRpc::XmlRpcValue &result) |
ROSCPP_DECL void | spin (Spinner &spinner) |
Enter simple event loop. | |
ROSCPP_DECL void | spin () |
Enter simple event loop. | |
ROSCPP_DECL void | spinOnce () |
Process a single round of callbacks. | |
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.). | |
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. | |
ssize_t | write_signal (const signal_fd_t &signal, const void *buffer, const size_t &nbyte) |
Variables | |
static bool | g_atexit_registered = false |
ConnectionManagerPtr | g_connection_manager |
boost::mutex | g_connection_manager_mutex |
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 |
PollManagerPtr | g_poll_manager |
boost::mutex | g_poll_manager_mutex |
ROSOutAppenderPtr | g_rosout_appender |
ServiceManagerPtr | g_service_manager |
boost::mutex | g_service_manager_mutex |
static bool | g_shutdown_requested = false |
static volatile bool | g_shutting_down = false |
static boost::recursive_mutex | g_shutting_down_mutex |
static boost::mutex | g_start_mutex |
static bool | g_started = false |
static InternalTimerManagerPtr | g_timer_manager |
TopicManagerPtr | g_topic_manager |
boost::mutex | g_topic_manager_mutex |
XMLRPCManagerPtr | g_xmlrpc_manager |
boost::mutex | g_xmlrpc_manager_mutex |
typedef boost::shared_ptr<AsyncSpinnerImpl> ros::AsyncSpinnerImplPtr |
typedef boost::shared_ptr<ASyncXMLRPCConnection> ros::ASyncXMLRPCConnectionPtr |
Definition at line 70 of file xmlrpc_manager.h.
typedef boost::shared_ptr< CallbackInterface > ros::CallbackInterfacePtr |
Definition at line 74 of file callback_queue_interface.h.
typedef boost::shared_ptr<CallbackQueue> ros::CallbackQueuePtr |
Definition at line 172 of file callback_queue.h.
typedef boost::shared_ptr< ConnectionManager > ros::ConnectionManagerPtr |
Definition at line 35 of file connection_manager.h.
typedef boost::shared_ptr< Connection > ros::ConnectionPtr |
Definition at line 56 of file connection.h.
typedef boost::function<bool(const ConnectionPtr&, const Header&)> ros::HeaderReceivedFunc |
Definition at line 61 of file connection.h.
typedef TimerManager<WallTime, WallDuration, WallTimerEvent> ros::InternalTimerManager |
Definition at line 38 of file internal_timer_manager.h.
typedef boost::shared_ptr<InternalTimerManager> ros::InternalTimerManagerPtr |
Definition at line 40 of file internal_timer_manager.h.
typedef boost::shared_ptr< IntraProcessPublisherLink > ros::IntraProcessPublisherLinkPtr |
Definition at line 67 of file intraprocess_publisher_link.h.
typedef boost::shared_ptr< IntraProcessSubscriberLink > ros::IntraProcessSubscriberLinkPtr |
Definition at line 37 of file intraprocess_publisher_link.h.
typedef std::list<ServicePublicationPtr> ros::L_ServicePublication |
Definition at line 81 of file forwards.h.
typedef std::list<ServiceServerLinkPtr> ros::L_ServiceServerLink |
Definition at line 85 of file forwards.h.
typedef std::list<SubscriptionPtr> ros::L_Subscription |
Definition at line 73 of file forwards.h.
typedef std::map< std::string, std::string > ros::M_string |
Definition at line 94 of file forwards.h.
typedef boost::shared_ptr<M_string> ros::M_stringPtr |
typedef boost::shared_ptr< MessageDeserializer > ros::MessageDeserializerPtr |
Definition at line 61 of file message_deserializer.h.
typedef boost::shared_ptr<NodeHandle> ros::NodeHandlePtr |
Definition at line 88 of file forwards.h.
typedef boost::shared_ptr< PollManager > ros::PollManagerPtr |
Definition at line 32 of file connection_manager.h.
typedef boost::shared_ptr< Publication > ros::PublicationPtr |
Definition at line 64 of file forwards.h.
typedef boost::weak_ptr< Publication > ros::PublicationWPtr |
Definition at line 58 of file rosout_appender.h.
typedef boost::shared_ptr< PublisherLink > ros::PublisherLinkPtr |
Definition at line 76 of file forwards.h.
typedef boost::function<void(const ConnectionPtr&, const boost::shared_array<uint8_t>&, uint32_t, bool)> ros::ReadFinishedFunc |
Definition at line 58 of file connection.h.
typedef log4cxx::helpers::ObjectPtrT<ROSOutAppender> ros::ROSOutAppenderPtr |
Definition at line 88 of file rosout_appender.h.
typedef std::set<ASyncXMLRPCConnectionPtr> ros::S_ASyncXMLRPCConnection |
Definition at line 71 of file xmlrpc_manager.h.
typedef std::set<ConnectionPtr> ros::S_Connection |
Definition at line 62 of file forwards.h.
typedef std::set<std::string> ros::S_string |
Definition at line 93 of file forwards.h.
typedef std::set<SubscriptionPtr> ros::S_Subscription |
Definition at line 75 of file forwards.h.
typedef boost::shared_ptr<ServiceCallbackHelper> ros::ServiceCallbackHelperPtr |
Definition at line 157 of file service_callback_helper.h.
typedef boost::shared_ptr< ServiceClientLink > ros::ServiceClientLinkPtr |
Definition at line 84 of file service_client_link.h.
typedef boost::shared_ptr<ServiceClient> ros::ServiceClientPtr |
Definition at line 206 of file service_client.h.
typedef boost::shared_ptr< ServiceManager > ros::ServiceManagerPtr |
Definition at line 167 of file forwards.h.
typedef boost::shared_ptr< ServicePublication > ros::ServicePublicationPtr |
Definition at line 79 of file forwards.h.
typedef boost::weak_ptr<ServicePublication> ros::ServicePublicationWPtr |
Definition at line 43 of file service_client_link.h.
typedef boost::shared_ptr< ServiceServerLink > ros::ServiceServerLinkPtr |
Definition at line 83 of file forwards.h.
typedef int ros::signal_fd_t |
typedef int ros::socket_fd_t |
typedef struct pollfd ros::socket_pollfd |
typedef std::pair<std::string, std::string> ros::StringPair |
Definition at line 95 of file forwards.h.
typedef boost::shared_ptr<SubscriberCallbacks> ros::SubscriberCallbacksPtr |
Definition at line 129 of file forwards.h.
typedef boost::shared_ptr< SubscriberLink > ros::SubscriberLinkPtr |
Definition at line 67 of file forwards.h.
typedef boost::function<void(const SingleSubscriberPublisher&)> ros::SubscriberStatusCallback |
Definition at line 97 of file forwards.h.
typedef boost::shared_ptr< SubscriptionCallbackHelper > ros::SubscriptionCallbackHelperPtr |
Definition at line 42 of file message_deserializer.h.
typedef boost::shared_ptr<SubscriptionCallback> ros::SubscriptionCallbackPtr |
Definition at line 42 of file subscription.h.
typedef boost::shared_ptr< Subscription > ros::SubscriptionPtr |
Definition at line 70 of file forwards.h.
typedef boost::shared_ptr<SubscriptionQueue> ros::SubscriptionQueuePtr |
Definition at line 45 of file subscription.h.
typedef boost::weak_ptr< Subscription > ros::SubscriptionWPtr |
Definition at line 72 of file forwards.h.
typedef boost::function<void(const TimerEvent&)> ros::TimerCallback |
Definition at line 147 of file forwards.h.
typedef boost::shared_ptr< TopicManager > ros::TopicManagerPtr |
Definition at line 169 of file forwards.h.
typedef boost::shared_ptr< Transport > ros::TransportPtr |
Definition at line 54 of file connection.h.
typedef boost::shared_ptr<TransportPublisherLink> ros::TransportPublisherLinkPtr |
Definition at line 88 of file transport_publisher_link.h.
typedef boost::shared_ptr<TransportSubscriberLink> ros::TransportSubscriberLinkPtr |
Definition at line 74 of file transport_subscriber_link.h.
typedef boost::shared_ptr< TransportTCP > ros::TransportTCPPtr |
Definition at line 56 of file forwards.h.
typedef struct ros::TransportUDPHeader ros::TransportUDPHeader |
typedef boost::shared_ptr< TransportUDP > ros::TransportUDPPtr |
Definition at line 58 of file forwards.h.
typedef std::vector<ConnectionPtr> ros::V_Connection |
Definition at line 63 of file forwards.h.
typedef std::vector<PublicationPtr> ros::V_Publication |
Definition at line 66 of file forwards.h.
typedef std::vector<Publisher> ros::V_Publisher |
Definition at line 199 of file publisher.h.
typedef std::vector<PublisherLinkPtr> ros::V_PublisherLink |
Definition at line 78 of file forwards.h.
typedef std::vector<ServiceClientLinkPtr> ros::V_ServiceClientLink |
Definition at line 50 of file service_publication.h.
typedef std::vector<ServicePublicationPtr> ros::V_ServicePublication |
Definition at line 82 of file forwards.h.
typedef std::vector<ServiceServer> ros::V_ServiceServer |
Definition at line 106 of file service_server.h.
typedef std::vector<std::string> ros::V_string |
Definition at line 92 of file forwards.h.
typedef std::vector<Subscriber> ros::V_Subscriber |
Definition at line 115 of file subscriber.h.
typedef std::vector< SubscriberLinkPtr > ros::V_SubscriberLink |
Definition at line 69 of file forwards.h.
typedef std::vector<SubscriptionPtr> ros::V_Subscription |
Definition at line 74 of file forwards.h.
typedef boost::shared_ptr<void const> ros::VoidConstPtr |
Definition at line 50 of file forwards.h.
typedef boost::weak_ptr<void const> ros::VoidConstWPtr |
Definition at line 51 of file forwards.h.
typedef boost::function<void(void)> ros::VoidFunc |
Definition at line 38 of file poll_manager.h.
typedef boost::shared_ptr<void> ros::VoidPtr |
Definition at line 48 of file forwards.h.
typedef boost::signal<void(void)> ros::VoidSignal |
Definition at line 37 of file poll_manager.h.
typedef boost::weak_ptr<void> ros::VoidWPtr |
Definition at line 49 of file forwards.h.
typedef std::vector<std::pair<std::string, std::string> > ros::VP_string |
Definition at line 91 of file forwards.h.
typedef boost::function<void(const WallTimerEvent&)> ros::WallTimerCallback |
Definition at line 165 of file forwards.h.
typedef boost::function<void(const ConnectionPtr&)> ros::WriteFinishedFunc |
Definition at line 59 of file connection.h.
typedef boost::shared_ptr<XMLRPCCallWrapper> ros::XMLRPCCallWrapperPtr |
Definition at line 57 of file xmlrpc_manager.h.
typedef boost::function<void(XmlRpc::XmlRpcValue&, XmlRpc::XmlRpcValue&)> ros::XMLRPCFunc |
Definition at line 92 of file xmlrpc_manager.h.
typedef boost::shared_ptr< XMLRPCManager > ros::XMLRPCManagerPtr |
Definition at line 173 of file forwards.h.
void ros::assignServiceConnectionHeader | ( | T * | , | |
const boost::shared_ptr< M_string > & | , | |||
typename boost::disable_if< ros::message_traits::IsMessage< T > >::type * | _ = 0 | |||
) | [inline] |
Definition at line 61 of file service_callback_helper.h.
void ros::assignServiceConnectionHeader | ( | T * | t, | |
const boost::shared_ptr< M_string > & | connection_header, | |||
typename boost::enable_if< ros::message_traits::IsMessage< T > >::type * | _ = 0 | |||
) | [inline] |
Definition at line 52 of file service_callback_helper.h.
void ros::assignSubscriptionConnectionHeader | ( | T * | t, | |
const boost::shared_ptr< M_string > & | connection_header, | |||
typename boost::disable_if< ros::message_traits::IsMessage< T > >::type * | _ = 0 | |||
) | [inline] |
Definition at line 86 of file subscription_callback_helper.h.
void ros::assignSubscriptionConnectionHeader | ( | T * | t, | |
const boost::shared_ptr< M_string > & | connection_header, | |||
typename boost::enable_if< ros::message_traits::IsMessage< T > >::type * | _ = 0 | |||
) | [inline] |
Definition at line 77 of file subscription_callback_helper.h.
void ros::clockCallback | ( | const rosgraph_msgs::Clock::ConstPtr & | msg | ) |
void ros::close_signal_pair | ( | signal_fd_t | signal_pair[2] | ) | [inline] |
int ros::close_socket | ( | socket_fd_t & | socket | ) |
bool ros::closeAllConnections | ( | roscpp::Empty::Request & | , | |
roscpp::Empty::Response & | ||||
) |
void ros::closeTransport | ( | const TransportUDPPtr & | trans | ) |
Definition at line 435 of file subscription.cpp.
int ros::create_signal_pair | ( | signal_fd_t | signal_pair[2] | ) |
ROS_DEPRECATED boost::shared_ptr<M> ros::defaultMessageCreateFunction | ( | ) | [inline] |
Definition at line 59 of file message_event.h.
boost::shared_ptr<M> ros::defaultServiceCreateFunction | ( | ) | [inline] |
Definition at line 68 of file service_callback_helper.h.
void ros::disableAllSignalsInThisThread | ( | ) |
Definition at line 49 of file common.cpp.
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()/NodeHandleadvertise()/etc. functions.
CallbackQueuePtr ros::getInternalCallbackQueue | ( | ) |
InternalTimerManagerPtr ros::getInternalTimerManager | ( | ) |
Definition at line 34 of file internal_timer_manager.cpp.
bool ros::getLoggers | ( | roscpp::GetLoggers::Request & | , | |
roscpp::GetLoggers::Response & | resp | |||
) |
void ros::getPid | ( | const XmlRpcValue & | params, | |
XmlRpcValue & | result | |||
) |
Definition at line 90 of file xmlrpc_manager.cpp.
void ros::init | ( | const VP_string & | remapping_args, | |
const std::string & | name, | |||
uint32_t | options = 0 | |||
) |
alternate ROS initialization function.
remappings | A vector<pair<string, string> > where each one constitutes a name remapping, or one of the special remappings like __name, __master, __ns, etc. | |
name | Name 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) |
InvalidNodeNameException | If the name passed in is not a valid "base" name |
void ros::init | ( | const M_string & | remappings, | |
const std::string & | name, | |||
uint32_t | options = 0 | |||
) |
alternate ROS initialization function.
remappings | A map<string, string> where each one constitutes a name remapping, or one of the special remappings like __name, __master, __ns, etc. | |
name | Name 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) |
InvalidNodeNameException | If the name passed in is not a valid "base" name |
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
argc | ||
argv | ||
name | Name 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) |
InvalidNodeNameException | If the name passed in is not a valid "base" name |
void ros::initInternalTimerManager | ( | ) |
Definition at line 39 of file internal_timer_manager.cpp.
bool ros::isInitialized | ( | ) |
Returns whether or not ros::init() has been called.
bool ros::isShuttingDown | ( | ) |
Returns whether or not ros::shutdown() has been (or is being) called.
bool ros::isStarted | ( | ) |
Returns whether or not the node has been started through ros::start().
bool ros::md5sumsMatch | ( | const std::string & | lhs, | |
const std::string & | rhs | |||
) |
Definition at line 199 of file topic_manager.cpp.
bool ros::ok | ( | ) |
Check whether it's time to exit.
ok() becomes false once ros::shutdown() has been called and is finished
int ros::poll_sockets | ( | 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.
fds | - the socket set (descriptor's and events) to poll for. | |
nfds | - the number of descriptors to poll for. | |
timeout | - timeout in milliseconds. |
ssize_t ros::read_signal | ( | const signal_fd_t & | signal, | |
void * | buffer, | |||
const size_t & | nbyte | |||
) | [inline] |
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
argc | the number of command-line arguments | |
argv | the command-line arguments | |
[out] | args_out | Output args, stripped of any ROS args |
void ros::requestShutdown | ( | ) |
Request that the node shut itself down from within a ROS thread.
This method signals a ROS thread to call shutdown().
int ros::set_non_blocking | ( | socket_fd_t & | socket | ) |
bool ros::setLoggerLevel | ( | roscpp::SetLoggerLevel::Request & | req, | |
roscpp::SetLoggerLevel::Response & | ||||
) |
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.
void ros::shutdownCallback | ( | XmlRpc::XmlRpcValue & | params, | |
XmlRpc::XmlRpcValue & | result | |||
) |
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.
spinner | a spinner to use to call callbacks. Two default implementations are available, SingleThreadedSpinner and MultiThreadedSpinner |
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.
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.
void ros::spinThread | ( | ) |
Definition at line 141 of file node_handle.cpp.
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())
bool ros::urisEqual | ( | const std::string & | uri1, | |
const std::string & | uri2 | |||
) |
Definition at line 198 of file subscription.cpp.
void ros::waitForShutdown | ( | ) |
Wait for this node to be shutdown, whether through Ctrl-C, ros::shutdown(), or similar.
ssize_t ros::write_signal | ( | const signal_fd_t & | signal, | |
const void * | buffer, | |||
const size_t & | nbyte | |||
) | [inline] |
bool ros::g_atexit_registered = false [static] |
Definition at line 39 of file connection_manager.cpp.
boost::mutex ros::g_connection_manager_mutex |
Definition at line 40 of file connection_manager.cpp.
uint32_t ros::g_init_options = 0 [static] |
bool ros::g_initialized = false [static] |
boost::thread ros::g_internal_queue_thread [static] |
int32_t ros::g_nh_refcount = 0 |
Definition at line 53 of file node_handle.cpp.
boost::mutex ros::g_nh_refcount_mutex |
Definition at line 52 of file node_handle.cpp.
bool ros::g_node_started_by_nh = false |
Definition at line 54 of file node_handle.cpp.
Definition at line 36 of file poll_manager.cpp.
boost::mutex ros::g_poll_manager_mutex |
Definition at line 37 of file poll_manager.cpp.
Definition at line 55 of file service_manager.cpp.
boost::mutex ros::g_service_manager_mutex |
Definition at line 56 of file service_manager.cpp.
bool ros::g_shutdown_requested = false [static] |
volatile bool ros::g_shutting_down = false [static] |
boost::recursive_mutex ros::g_shutting_down_mutex [static] |
boost::mutex ros::g_start_mutex [static] |
bool ros::g_started = false [static] |
Definition at line 32 of file internal_timer_manager.cpp.
Definition at line 56 of file topic_manager.cpp.
boost::mutex ros::g_topic_manager_mutex |
Definition at line 57 of file topic_manager.cpp.
Definition at line 97 of file xmlrpc_manager.cpp.
boost::mutex ros::g_xmlrpc_manager_mutex |
Definition at line 98 of file xmlrpc_manager.cpp.