mocap_node.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2022, Mocap Nokov Company., Lika.Ji
3  * Copyright (c) 2018, Houston Mechatronics Inc., JD Yamokoski
4  * Copyright (c) 2012, Clearpath Robotics, Inc., Alex Bencz
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions are met:
9  *
10  * 1. Redistributions of source code must retain the above copyright notice,
11  * this list of conditions and the following disclaimer.
12  * 2. Redistributions in binary form must reproduce the above copyright
13  * notice, this list of conditions and the following disclaimer in the
14  * documentation and/or other materials provided with the distribution.
15  * 3. Neither the name of the copyright holder nor the names of its
16  * contributors may be used to endorse or promote products derived from
17  * this software without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
23  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29  * POSSIBILITY OF SUCH DAMAGE.
30  */
31 
32 // Local includes
34 #include <mocap_nokov/MocapNokovConfig.h>
35 #include <mocap_nokov/data_model.h>
37 // STL includes
38 #include <mutex>
39 // Ros includes
40 #include <ros/ros.h>
41 #include <dynamic_reconfigure/server.h>
42 // SDK includes
43 #include <NokovSDKClient.h>
44 
45 namespace mocap_nokov
46 {
47  std::mutex mtx;
49 
50  void DataHandler(sFrameOfMocapData* pFrameOfData, void* pUserData)
51  {
52  if (nullptr == pFrameOfData)
53  return;
54 
55  // Store the frame
56  std::lock_guard<std::mutex> lck (mtx);
57 
58  int nmaker = (pFrameOfData->nOtherMarkers < MAX_MARKERS)?pFrameOfData->nOtherMarkers:MAX_MARKERS;
59 
60  frameObjData.frameNumber = pFrameOfData->iFrame;
61  frameObjData.dataFrame.markerSets.resize(pFrameOfData->nMarkerSets);
62  frameObjData.dataFrame.rigidBodies.resize(pFrameOfData->nRigidBodies);
63  frameObjData.dataFrame.otherMarkers.resize(pFrameOfData->nOtherMarkers);
64  frameObjData.dataFrame.latency = pFrameOfData->fLatency;
65 
66  for(int i = 0; i< nmaker; ++i)
67  {
69  Marker{pFrameOfData->OtherMarkers[i][0] * 0.001f,
70  pFrameOfData->OtherMarkers[i][1] * 0.001f,
71  pFrameOfData->OtherMarkers[i][2] * 0.001f}
72  );
73  }
74 
75  for(int i = 0; i< pFrameOfData->nRigidBodies; ++i)
76  {
77  RigidBody body;
78  body.bodyId = pFrameOfData->RigidBodies[i].ID;
79  body.iFrame = pFrameOfData->iFrame;
80  body.isTrackingValid = true;
81  body.pose.position = {pFrameOfData->RigidBodies[i].x * 0.001f,
82  pFrameOfData->RigidBodies[i].y * 0.001f,
83  pFrameOfData->RigidBodies[i].z * 0.001f};
84 
85  body.pose.orientation = {pFrameOfData->RigidBodies[i].qx,
86  pFrameOfData->RigidBodies[i].qy,
87  pFrameOfData->RigidBodies[i].qz,
88  pFrameOfData->RigidBodies[i].qw};
89 
90  frameObjData.dataFrame.rigidBodies.push_back(body);
91  }
92  }
93 
95  {
96  static DataModel frame;
97  {
98  std::lock_guard<std::mutex> lck (mtx);
99  frame = frameObjData;
100  }
101  return frame;
102  }
103 
105  {
106  public:
109  ServerDescription const& serverDescr,
110  PublisherConfigurations const& pubConfigs) :
111  nh(nh),
112  server(ros::NodeHandle("~/nokov_config")),
113  serverDescription(serverDescr),
114  publisherConfigurations(pubConfigs)
115  {
116  server.setCallback(boost::bind(&NokovRosBridge::reconfigureCallback, this, _1, _2));
117  }
118 
119  void reconfigureCallback(MocapNokovConfig& config, uint32_t)
120  {
121  serverDescription.IpAddress = config.server_address;
122 
123  initialize();
124  }
125 
126  void initialize()
127  {
128  // Create client
129  sdkClientPtr.reset(new NokovSDKClient());
130  sdkClientPtr->SetDataCallback(DataHandler);
131 
132  unsigned char sdkVersion[4] = {0};
133  sdkClientPtr->NokovSDKVersion(sdkVersion);
134  Version ver((int)sdkVersion[0], (int)sdkVersion[1], (int)sdkVersion[2], (int)sdkVersion[3]);
135  ROS_INFO("Load SDK Ver:%s", (char*)ver.getVersionString().c_str());
136 
137  while(ros::ok() && sdkClientPtr->Initialize((char*)serverDescription.IpAddress.c_str()))
138  {
139  ROS_WARN("Connecting to server again");
140  ros::Duration(2.).sleep();
141  }
142 
143  // Once we have the server info, create publishers
144  publishDispatcherPtr.reset(
147 
148  ROS_INFO("Initialization complete");
149 
150  initialized = true;
151  };
152 
153  void run()
154  {
155  while (ros::ok())
156  {
157  if (initialized)
158  {
159  static int preIFrame = 0;
160 
161  const auto frame = GetCurrentFrame();
162 
163  if (frame.frameNumber != preIFrame)
164  {
165  preIFrame = frame.frameNumber ;
166 
167  const ros::Time time = ros::Time::now();
168 
169  publishDispatcherPtr->publish(time, frame.dataFrame.rigidBodies);
170  }
171 
172  usleep(100);
173  }
174  else
175  {
176  ros::Duration(1.).sleep();
177  }
178  ros::spinOnce();
179  }
180  }
181 
182  private:
187  std::unique_ptr<RigidBodyPublishDispatcher> publishDispatcherPtr;
188  std::unique_ptr<NokovSDKClient> sdkClientPtr;
189  dynamic_reconfigure::Server<MocapNokovConfig> server;
190  };
191 
192 } // namespace
193 
194 
196 int main( int argc, char* argv[] )
197 {
198  // Initialize ROS nh
199  ros::init(argc, argv, "mocap_nh");
200  ros::NodeHandle nh("~");
201 
202  // Grab nh configuration from rosparam
203  mocap_nokov::ServerDescription serverDescription;
204  mocap_nokov::PublisherConfigurations publisherConfigurations;
205  mocap_nokov::NodeConfiguration::fromRosParam(nh, serverDescription, publisherConfigurations);
206 
207  // Create nh object, initialize and run
208  mocap_nokov::NokovRosBridge nb(nh, serverDescription, publisherConfigurations);
209  nb.initialize();
210  nb.run();
211 
212  return 0;
213 }
mocap_nokov::DataHandler
void DataHandler(sFrameOfMocapData *pFrameOfData, void *pUserData)
Definition: mocap_node.cpp:50
mocap_nokov::NokovRosBridge::publishDispatcherPtr
std::unique_ptr< RigidBodyPublishDispatcher > publishDispatcherPtr
Definition: mocap_node.cpp:187
mocap_nokov::NokovRosBridge::run
void run()
Definition: mocap_node.cpp:153
mocap_nokov::RigidBody::iFrame
int iFrame
Definition: data_model.h:69
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
mocap_nokov::Version
\breif Version class containing the version information and helpers for comparison.
Definition: version.h:39
ros
ros.h
sFrameOfMocapData::fLatency
float fLatency
Definition: NokovSDKTypes.h:317
sFrameOfMocapData::iFrame
int iFrame
Definition: NokovSDKTypes.h:304
sRigidBodyData::qx
float qx
Definition: NokovSDKTypes.h:228
ros::spinOnce
ROSCPP_DECL void spinOnce()
sRigidBodyData::ID
int ID
Definition: NokovSDKTypes.h:226
mocap_nokov::ServerDescription::IpAddress
std::string IpAddress
Definition: mocap_config.h:51
mocap_nokov::Version::getVersionString
std::string const & getVersionString() const
Definition: version.cpp:69
mocap_nokov::RigidBody::pose
Pose pose
Definition: data_model.h:71
NokovSDKClient
Definition: NokovSDKClient.h:34
sRigidBodyData::qy
float qy
Definition: NokovSDKTypes.h:228
sRigidBodyData::y
float y
Definition: NokovSDKTypes.h:227
mocap_nokov::ServerDescription
Server communication info.
Definition: mocap_config.h:43
mocap_nokov::PublisherConfigurations
std::vector< PublisherConfiguration > PublisherConfigurations
Definition: mocap_config.h:72
mocap_nokov::GetCurrentFrame
const DataModel & GetCurrentFrame()
Definition: mocap_node.cpp:94
ros::ok
ROSCPP_DECL bool ok()
mocap_nokov::Marker
Data object holding the position of a single mocap marker in 3d space.
Definition: data_model.h:43
sFrameOfMocapData::nOtherMarkers
int nOtherMarkers
Definition: NokovSDKTypes.h:307
mocap_nokov::RigidBody::bodyId
int bodyId
Definition: data_model.h:70
mocap_nokov::mtx
std::mutex mtx
Definition: mocap_node.cpp:47
mocap_nokov::RigidBody::isTrackingValid
bool isTrackingValid
Definition: data_model.h:73
mocap_nokov::NokovRosBridge::serverDescription
ServerDescription serverDescription
Definition: mocap_node.cpp:185
mocap_nokov::NokovRosBridge::NokovRosBridge
NokovRosBridge(ros::NodeHandle &nh, ServerDescription const &serverDescr, PublisherConfigurations const &pubConfigs)
Definition: mocap_node.cpp:107
sFrameOfMocapData::OtherMarkers
MarkerData * OtherMarkers
Definition: NokovSDKTypes.h:308
mocap_nokov::frameObjData
DataModel frameObjData
Definition: mocap_node.cpp:48
main
int main(int argc, char *argv[])
Definition: mocap_node.cpp:196
sRigidBodyData::z
float z
Definition: NokovSDKTypes.h:227
sRigidBodyData::qz
float qz
Definition: NokovSDKTypes.h:228
ROS_WARN
#define ROS_WARN(...)
rigid_body_publisher.h
MAX_MARKERS
#define MAX_MARKERS
Definition: NokovSDKTypes.h:52
mocap_nokov::NokovRosBridge::initialized
bool initialized
Definition: mocap_node.cpp:184
sRigidBodyData::x
float x
Definition: NokovSDKTypes.h:227
mocap_nokov::NokovRosBridge::sdkClientPtr
std::unique_ptr< NokovSDKClient > sdkClientPtr
Definition: mocap_node.cpp:188
mocap_nokov::RigidBodyPublishDispatcher
Dispatches RigidBody data to the correct publisher.
Definition: rigid_body_publisher.h:66
mocap_nokov::NokovRosBridge
Definition: mocap_node.cpp:104
ros::Time
mocap_nokov::ModelFrame::latency
float latency
Definition: data_model.h:106
mocap_nokov::DataModel::dataFrame
ModelFrame dataFrame
Definition: data_model.h:116
mocap_nokov::NokovRosBridge::reconfigureCallback
void reconfigureCallback(MocapNokovConfig &config, uint32_t)
Definition: mocap_node.cpp:119
sRigidBodyData::qw
float qw
Definition: NokovSDKTypes.h:228
sFrameOfMocapData
Definition: NokovSDKTypes.h:302
mocap_nokov::NokovRosBridge::server
dynamic_reconfigure::Server< MocapNokovConfig > server
Definition: mocap_node.cpp:189
sFrameOfMocapData::nMarkerSets
int nMarkerSets
Definition: NokovSDKTypes.h:305
data_model.h
mocap_config.h
ros::Duration::sleep
bool sleep() const
mocap_nokov::NodeConfiguration::fromRosParam
static void fromRosParam(ros::NodeHandle &nh, ServerDescription &serverDescription, PublisherConfigurations &pubConfigs)
Definition: mocap_config.cpp:88
mocap_nokov::NokovRosBridge::nh
ros::NodeHandle nh
Definition: mocap_node.cpp:183
mocap_nokov::ModelFrame::otherMarkers
std::vector< Marker > otherMarkers
Definition: data_model.h:104
mocap_nokov
Definition: data_model.h:39
ROS_INFO
#define ROS_INFO(...)
sFrameOfMocapData::RigidBodies
sRigidBodyData RigidBodies[MAX_RIGIDBODIES]
Definition: NokovSDKTypes.h:310
mocap_nokov::ModelFrame::rigidBodies
std::vector< RigidBody > rigidBodies
Definition: data_model.h:105
NokovSDKClient.h
mocap_nokov::ModelFrame::markerSets
std::vector< MarkerSet > markerSets
Definition: data_model.h:103
mocap_nokov::DataModel
The data model for this node.
Definition: data_model.h:110
sFrameOfMocapData::nRigidBodies
int nRigidBodies
Definition: NokovSDKTypes.h:309
ros::Duration
mocap_nokov::NokovRosBridge::publisherConfigurations
PublisherConfigurations publisherConfigurations
Definition: mocap_node.cpp:186
mocap_nokov::RigidBody
Data object holding information about a single rigid body within a mocap skeleton.
Definition: data_model.h:66
mocap_nokov::DataModel::frameNumber
int frameNumber
Definition: data_model.h:115
ros::NodeHandle
mocap_nokov::NokovRosBridge::initialize
void initialize()
Definition: mocap_node.cpp:126
ros::Time::now
static Time now()


mocap_nokov
Author(s):
autogenerated on Mon Mar 3 2025 03:08:00