Class JRosClientNode
java.lang.Object
edu.tufts.hrilab.ros2.Ros2Node
edu.tufts.hrilab.ros2.ros2jrosclient.JRosClientNode
Generic ROS2 node implementation using JROSClient. This may eventually be extracted to an
interface so we can swap out different ros2 java implementations.
-
Field Summary
FieldsModifier and TypeFieldDescriptionprotected id.jros2client.JRos2Client
Pub/sub managerpinorobotics.jros2tf2.JRos2Tf2
Fields inherited from class edu.tufts.hrilab.ros2.Ros2Node
actionList, log, publisherList, serviceList
-
Constructor Summary
Constructors -
Method Summary
Modifier and TypeMethodDescription<GOAL extends id.jrosmessages.Message,
RES extends id.jrosmessages.Message, DEF extends pinorobotics.jros2actionlib.actionlib_msgs.Action2Definition<GOAL, RES>>
voidvoid
addAndStartPublisher
(Ros2Publisher<?> pub) Convenience method to add and start a publisher indefinitely.void
addAndStartPublisher
(Ros2Publisher<?> pub, Integer iters) Conveinece method to add and start a publisher for the given number of iterations.void
addAndStartSubscriber
(Ros2Subscriber<?> sub) Adds the specified subscriber to the node.void
addPublisher
(Ros2Publisher<?> pub) Adds the specified publisher to the node.<REQ extends id.jrosmessages.Message,
RES extends id.jrosmessages.Message, DEF extends pinorobotics.jrosservices.msgs.ServiceDefinition<REQ, RES>>
voidaddService
(DEF definition, String serviceName) Creates a service...<GOAL extends id.jrosmessages.Message,
RES extends id.jrosmessages.Message>
REScallAction
(String actionName, GOAL goal) <REQ extends id.jrosmessages.Message,
RES extends id.jrosmessages.Message>
REScallService
(String serviceName, REQ message) void
createTf()
void
end()
Spins down the node.javax.vecmath.Matrix4d
lookupTransform
(String from, String to) void
oneTimePublish
(Ros2Publisher<?> pub) Convenience method to publish a message one time for a given publisher.void
removePublisher
(Ros2Publisher<?> pub) Stops and removes the publisher from the node.void
removeSubscriber
(Ros2Subscriber<?> sub) Removes the specified subscriber from the node.void
startPublisher
(Ros2Publisher<?> pub) Starts publishing the specified publisher indefinitely (assuming node is spinning).void
startPublisher
(Ros2Publisher<?> pub, Integer iters) Starts publishing the specified publisher for the given iterations (assuming node is pinning).void
stopPublisher
(Ros2Publisher<?> pub) Stops the given publisher from publishing.
-
Field Details
-
client
protected id.jros2client.JRos2Client clientPub/sub manager -
tf
public pinorobotics.jros2tf2.JRos2Tf2 tf
-
-
Constructor Details
-
JRosClientNode
public JRosClientNode() -
JRosClientNode
public JRosClientNode(int domain_id)
-
-
Method Details
-
addAndStartSubscriber
Description copied from class:Ros2Node
Adds the specified subscriber to the node. Immediately starts listening.- Specified by:
addAndStartSubscriber
in classRos2Node
- Parameters:
sub
- Subscriber to add to the node.
-
end
public void end()Description copied from class:Ros2Node
Spins down the node. All publishers will stop publishing. -
removeSubscriber
Description copied from class:Ros2Node
Removes the specified subscriber from the node. TODO: Currently no jrosclient functionality for this.- Specified by:
removeSubscriber
in classRos2Node
- Parameters:
sub
- Subscriber to remove from the node.
-
addPublisher
Description copied from class:Ros2Node
Adds the specified publisher to the node. Does not start publishing until the publisher is started.- Specified by:
addPublisher
in classRos2Node
- Parameters:
pub
- Publisher to add to the node.
-
startPublisher
Description copied from class:Ros2Node
Starts publishing the specified publisher indefinitely (assuming node is spinning). The node must have been added to the node.- Specified by:
startPublisher
in classRos2Node
- Parameters:
pub
- Existing publisher to be started
-
startPublisher
Description copied from class:Ros2Node
Starts publishing the specified publisher for the given iterations (assuming node is pinning). The node must have been added to the node.- Specified by:
startPublisher
in classRos2Node
- Parameters:
pub
- Existing publisher to be startediters
- Iterations the publisher publishes for
-
oneTimePublish
Description copied from class:Ros2Node
Convenience method to publish a message one time for a given publisher. Removed after use.- Specified by:
oneTimePublish
in classRos2Node
- Parameters:
pub
- Publisher to publish once
-
addAndStartPublisher
Description copied from class:Ros2Node
Convenience method to add and start a publisher indefinitely.- Specified by:
addAndStartPublisher
in classRos2Node
- Parameters:
pub
- Publisher to be added and started- See Also:
-
addAndStartPublisher
Description copied from class:Ros2Node
Conveinece method to add and start a publisher for the given number of iterations.- Specified by:
addAndStartPublisher
in classRos2Node
- Parameters:
pub
- Publisher to be added and startediters
- Number of iterations to publish for- See Also:
-
stopPublisher
Description copied from class:Ros2Node
Stops the given publisher from publishing. Can be started again.- Specified by:
stopPublisher
in classRos2Node
- Parameters:
pub
- Publisher to be stopped.
-
removePublisher
Description copied from class:Ros2Node
Stops and removes the publisher from the node. must be re-added to start again.- Specified by:
removePublisher
in classRos2Node
- Parameters:
pub
- Publisher to be stopped and removed
-
addService
public <REQ extends id.jrosmessages.Message,RES extends id.jrosmessages.Message, void addServiceDEF extends pinorobotics.jrosservices.msgs.ServiceDefinition<REQ, RES>> (DEF definition, String serviceName) Description copied from class:Ros2Node
Creates a service... This is definition is a nightmare. Should we just let users make this manually?- Specified by:
addService
in classRos2Node
-
callService
public <REQ extends id.jrosmessages.Message,RES extends id.jrosmessages.Message> RES callService(String serviceName, REQ message) - Specified by:
callService
in classRos2Node
-
createTf
public void createTf() -
lookupTransform
- Specified by:
lookupTransform
in classRos2Node
-
addAction
public <GOAL extends id.jrosmessages.Message,RES extends id.jrosmessages.Message, void addActionDEF extends pinorobotics.jros2actionlib.actionlib_msgs.Action2Definition<GOAL, RES>> (DEF def, String actionName) -
callAction
public <GOAL extends id.jrosmessages.Message,RES extends id.jrosmessages.Message> RES callAction(String actionName, GOAL goal) - Specified by:
callAction
in classRos2Node
-