mocap_node.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2018, Houston Mechatronics Inc., JD Yamokoski
3  * Copyright (c) 2012, Clearpath Robotics, Inc., Alex Bencz
4  * All rights reserved.
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright notice,
10  * this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in the
13  * documentation and/or other materials provided with the distribution.
14  * 3. Neither the name of the copyright holder nor the names of its
15  * contributors may be used to endorse or promote products derived from
16  * this software without specific prior written permission.
17  *
18  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
22  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28  * POSSIBILITY OF SUCH DAMAGE.
29  */
30 
31 // Local includes
32 #include <mocap_optitrack/socket.h>
36 #include <mocap_optitrack/MocapOptitrackConfig.h>
37 #include "natnet/natnet_messages.h"
38 
39 #include <dynamic_reconfigure/server.h>
40 #include <memory>
41 #include <ros/ros.h>
42 
43 
44 namespace mocap_optitrack
45 {
46 
48 {
49 public:
51  ServerDescription const& serverDescr,
52  PublisherConfigurations const& pubConfigs) :
53  nh(nh)
54  {
55  server.setCallback(boost::bind(&OptiTrackRosBridge::reconfigureCallback, this, _1, _2));
56  serverDescription = serverDescr;
57  publisherConfigurations = pubConfigs;
58  }
59 
60  void reconfigureCallback(MocapOptitrackConfig& config, uint32_t)
61  {
62  serverDescription.enableOptitrack = config.enable_optitrack;
63  serverDescription.commandPort = config.command_port;
64  serverDescription.dataPort = config.data_port;
65  serverDescription.multicastIpAddress = config.multicast_address;
66 
67  initialize();
68  }
69 
70  void initialize()
71  {
73  {
74  // Create socket
78 
79  if (!serverDescription.version.empty())
80  {
82  }
83 
84  // Need verion information from the server to properly decode any of their packets.
85  // If we have not recieved that yet, send another request.
86  while (ros::ok() && !dataModel.hasServerInfo())
87  {
88  natnet::ConnectionRequestMessage connectionRequestMsg;
89  natnet::MessageBuffer connectionRequestMsgBuffer;
90  connectionRequestMsg.serialize(connectionRequestMsgBuffer, NULL);
91  int ret = multicastClientSocketPtr->send(
92  &connectionRequestMsgBuffer[0],
93  connectionRequestMsgBuffer.size(),
95  if (updateDataModelFromServer()) usleep(10);
96  ros::spinOnce();
97  }
98  // Once we have the server info, create publishers
103  ROS_INFO("Initialization complete");
104  initialized = true;
105  }
106  else
107  {
108  ROS_INFO("Initialization incomplete");
109  initialized = false;
110  }
111  };
112 
113  void run()
114  {
115  while (ros::ok())
116  {
117  if (initialized)
118  {
120  {
121  // Maybe we got some data? If we did it would be in the form of one or more
122  // rigid bodies in the data model
123  ros::Time time = ros::Time::now();
125 
126  // Clear out the model to prepare for the next frame of data
127  dataModel.clear();
128 
129  // If we processed some data, take a short break
130  usleep(10);
131  }
132  }
133  else
134  {
135  ros::Duration(1.).sleep();
136  }
137  ros::spinOnce();
138  }
139  }
140 
141 private:
143  {
144  // Get data from mocap server
145  int numBytesReceived = multicastClientSocketPtr->recv();
146  if (numBytesReceived > 0)
147  {
148  // Grab latest message buffer
149  const char* pMsgBuffer = multicastClientSocketPtr->getBuffer();
150 
151  // Copy char* buffer into MessageBuffer and dispatch to be deserialized
152  natnet::MessageBuffer msgBuffer(pMsgBuffer, pMsgBuffer + numBytesReceived);
154 
155  return true;
156  }
157 
158  return false;
159  };
160 
165  std::unique_ptr<UdpMulticastSocket> multicastClientSocketPtr;
166  std::unique_ptr<RigidBodyPublishDispatcher> publishDispatcherPtr;
167  dynamic_reconfigure::Server<MocapOptitrackConfig> server;
169 };
170 
171 } // namespace mocap_optitrack
172 
173 
175 int main(int argc, char* argv[])
176 {
177  // Initialize ROS node
178  ros::init(argc, argv, "mocap_node");
179  ros::NodeHandle nh("~");
180 
181  // Grab node configuration from rosparam
184  mocap_optitrack::NodeConfiguration::fromRosParam(nh, serverDescription, publisherConfigurations);
185 
186  // Create node object, initialize and run
187  mocap_optitrack::OptiTrackRosBridge node(nh, serverDescription, publisherConfigurations);
188  node.initialize();
189  node.run();
190 
191  return 0;
192 }
static void dispatch(MessageBuffer const &, mocap_optitrack::DataModel *)
Version const & getNatNetVersion() const
Definition: data_model.cpp:94
bool sleep() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
PublisherConfigurations publisherConfigurations
Definition: mocap_node.cpp:163
OptiTrackRosBridge(ros::NodeHandle &nh, ServerDescription const &serverDescr, PublisherConfigurations const &pubConfigs)
Definition: mocap_node.cpp:50
static void fromRosParam(ros::NodeHandle &nh, ServerDescription &serverDescription, PublisherConfigurations &pubConfigs)
std::vector< char > MessageBuffer
std::vector< RigidBody > rigidBodies
Definition: data_model.h:105
bool hasServerInfo() const
Definition: data_model.h:132
#define ROS_INFO(...)
Dispatches RigidBody data to the correct publisher.
ROSCPP_DECL bool ok()
int main(int argc, char *argv[])
Definition: mocap_node.cpp:175
dynamic_reconfigure::Server< MocapOptitrackConfig > server
Definition: mocap_node.cpp:167
The data model for this node.
Definition: data_model.h:119
std::unique_ptr< UdpMulticastSocket > multicastClientSocketPtr
Definition: mocap_node.cpp:165
std::vector< PublisherConfiguration > PublisherConfigurations
Definition: mocap_config.h:77
virtual void serialize(MessageBuffer &msgBuffer, mocap_optitrack::DataModel const *)
std::unique_ptr< RigidBodyPublishDispatcher > publishDispatcherPtr
Definition: mocap_node.cpp:166
static Time now()
Allows to retrieve data from a UDP multicast group.
Definition: socket.h:55
void reconfigureCallback(MocapOptitrackConfig &config, uint32_t)
Definition: mocap_node.cpp:60
void setVersions(int *nver, int *sver)
Definition: data_model.cpp:87
ROSCPP_DECL void spinOnce()
Server communication info.
Definition: mocap_config.h:42


mocap_optitrack
Author(s): Kathrin Gräve , Alex Bencz/ , Tony Baltovski , JD Yamokoski
autogenerated on Fri Mar 26 2021 02:05:51