NodeHandle Functions
ROS.NodeHandle
ROS.advertise
ROS.advertiseService
ROS.deleteParam
ROS.hasParam
ROS.param
ROS.param
ROS.param
ROS.param
ROS.param
ROS.serviceClient
ROS.setParam
ROS.setParam
ROS.setParam
ROS.setParam
ROS.setParam
ROS.shutdown
ROS.subscribe
ROS.NodeHandle
— MethodNodeHandle()
Create a NodeHandle.
ROS.advertise
— Methodadvertise(nodehandle, topic_name::String, topic_type, queue_size::Int)
Advertise a topic.
ROS.advertiseService
— MethodadvertiseService(nodehandle, service_name::String, service_request_type, service_response_type, callback)
Advertise a service.
ROS.deleteParam
— MethoddeleteParam(n, key::String)
Delete a parameter from the parameter server.
ROS.hasParam
— MethodhasParam(n, key::String)
Check whether a parameter exists on the parameter server.
ROS.param
— Methodparam(n, key::String, default::Bool)
Assign value from parameter server, with default.
ROS.param
— Methodparam(n, key::String, default::Float64)
Assign value from parameter server, with default.
ROS.param
— Methodparam(n, key::String, default::Int32)
Assign value from parameter server, with default.
ROS.param
— Methodparam(n, key::String, default::Int64)
Assign value from parameter server, with default.
ROS.param
— Methodparam(n, key::String, default::String)
Assign value from parameter server, with default.
ROS.serviceClient
— MethodserviceClient(nodehandle, topic_name::String, topic_type)
Create a client for a service.
ROS.setParam
— MethodsetParam(n, key::String, value::Bool)
Set a value ont the parameter server.
ROS.setParam
— MethodsetParam(n, key::String, value::Float64)
Set a value ont the parameter server.
ROS.setParam
— MethodsetParam(n, key::String, value::Int32)
Set a value ont the parameter server.
ROS.setParam
— MethodsetParam(n, key::String, value::Int64)
Set a value ont the parameter server.
ROS.setParam
— MethodsetParam(n, key::String, value::String)
Set a value ont the parameter server.
ROS.shutdown
— Methodshutdown(n)
Shutdown every handle created through this
NodeHandle.
ROS.subscribe
— Methodsubscribe(nodehandle, topic_name::String, queue_size::Int, topic_type, callback)
Subscribe to a topic.