36 #include <mocap_optitrack/MocapOptitrackConfig.h> 39 #include <dynamic_reconfigure/server.h> 53 nh(nh),
server(
ros::NodeHandle(
"~/optitrack_config"))
90 connectionRequestMsg.
serialize(connectionRequestMsgBuffer, NULL);
92 &connectionRequestMsgBuffer[0],
93 connectionRequestMsgBuffer.size(),
105 ROS_INFO(
"Initialization complete");
110 ROS_INFO(
"Initialization incomplete");
147 if (numBytesReceived > 0)
168 dynamic_reconfigure::Server<MocapOptitrackConfig>
server;
176 int main(
int argc,
char* argv[])
static void dispatch(MessageBuffer const &, mocap_optitrack::DataModel *)
bool updateDataModelFromServer()
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
PublisherConfigurations publisherConfigurations
std::string multicastIpAddress
OptiTrackRosBridge(ros::NodeHandle &nh, ServerDescription const &serverDescr, PublisherConfigurations const &pubConfigs)
static void fromRosParam(ros::NodeHandle &nh, ServerDescription &serverDescription, PublisherConfigurations &pubConfigs)
Version const & getNatNetVersion() const
std::vector< char > MessageBuffer
std::vector< RigidBody > rigidBodies
Dispatches RigidBody data to the correct publisher.
bool hasServerInfo() const
int main(int argc, char *argv[])
dynamic_reconfigure::Server< MocapOptitrackConfig > server
The data model for this node.
std::unique_ptr< UdpMulticastSocket > multicastClientSocketPtr
std::vector< PublisherConfiguration > PublisherConfigurations
virtual void serialize(MessageBuffer &msgBuffer, mocap_optitrack::DataModel const *)
std::vector< int > version
std::unique_ptr< RigidBodyPublishDispatcher > publishDispatcherPtr
Allows to retrieve data from a UDP multicast group.
void reconfigureCallback(MocapOptitrackConfig &config, uint32_t)
void setVersions(int *nver, int *sver)
ROSCPP_DECL void spinOnce()
ServerDescription serverDescription
Server communication info.