void process_markers(const ros::Time& frame_time, unsigned int vicon_frame_num)
  {
    if (markers_pub.getNumSubscribers() > 0)
    {
      if (not marker_data_enabled)
      {
        MyClient.EnableMarkerData();
        ROS_ASSERT(MyClient.IsMarkerDataEnabled().Enabled);
        marker_data_enabled = true;
      }
      if (not unlabeled_marker_data_enabled)
      {
        MyClient.EnableUnlabeledMarkerData();
        ROS_ASSERT(MyClient.IsUnlabeledMarkerDataEnabled().Enabled);
        unlabeled_marker_data_enabled = true;
      }
      n_markers = 0;
      vicon_mocap::Markers markers_msg;
      markers_msg.header.stamp = frame_time;
      markers_msg.frame_number = vicon_frame_num;
      markers_msg.header.frame_id = tf_ref_frame_id;
      // Count the number of subjects
      unsigned int SubjectCount = MyClient.GetSubjectCount().SubjectCount;
      // Get labeled markers
      for (unsigned int SubjectIndex = 0; SubjectIndex < SubjectCount; ++SubjectIndex)
      {
        std::string this_subject_name = MyClient.GetSubjectName(SubjectIndex).SubjectName;
        // Count the number of markers
        unsigned int num_subject_markers = MyClient.GetMarkerCount(SubjectName).MarkerCount;
        n_markers += num_subject_markers;
        //std::cout << "    Markers (" << MarkerCount << "):" << std::endl;
        for (unsigned int MarkerIndex = 0; MarkerIndex < num_subject_markers; ++MarkerIndex)
        {
          vicon_mocap::Marker this_marker;
          this_marker.marker_name = MyClient.GetMarkerName(this_subject_name, MarkerIndex).MarkerName;
          this_marker.subject_name = this_subject_name;
          this_marker.segment_name
              = MyClient.GetMarkerParentName(this_subject_name, this_marker.marker_name).SegmentName;

          // Get the global marker translation
          Output_GetMarkerGlobalTranslation _Output_GetMarkerGlobalTranslation =
              MyClient.GetMarkerGlobalTranslation(this_subject_name, this_marker.marker_name);

          this_marker.translation.x = _Output_GetMarkerGlobalTranslation.Translation[0] / 1000;
          this_marker.translation.y = _Output_GetMarkerGlobalTranslation.Translation[1] / 1000;
          this_marker.translation.z = _Output_GetMarkerGlobalTranslation.Translation[2] / 1000;
          this_marker.occluded = _Output_GetMarkerGlobalTranslation.Occluded;

          markers_msg.markers.push_back(this_marker);
        }
      }
      // get unlabeled markers
      unsigned int UnlabeledMarkerCount = MyClient.GetUnlabeledMarkerCount().MarkerCount;
      //ROS_INFO("# unlabeled markers: %d", UnlabeledMarkerCount);
      n_markers += UnlabeledMarkerCount;
      n_unlabeled_markers = UnlabeledMarkerCount;
      for (unsigned int UnlabeledMarkerIndex = 0; UnlabeledMarkerIndex < UnlabeledMarkerCount; ++UnlabeledMarkerIndex)
      {
        // Get the global marker translation
        Output_GetUnlabeledMarkerGlobalTranslation _Output_GetUnlabeledMarkerGlobalTranslation =
            MyClient.GetUnlabeledMarkerGlobalTranslation(UnlabeledMarkerIndex);

        if (_Output_GetUnlabeledMarkerGlobalTranslation.Result == Result::Success)
        {
          vicon_mocap::Marker this_marker;
          this_marker.translation.x = _Output_GetUnlabeledMarkerGlobalTranslation.Translation[0] / 1000;
          this_marker.translation.y = _Output_GetUnlabeledMarkerGlobalTranslation.Translation[1] / 1000;
          this_marker.translation.z = _Output_GetUnlabeledMarkerGlobalTranslation.Translation[2] / 1000;
          this_marker.occluded = false; // unlabeled markers can't be occluded
          markers_msg.unlabeled_markers.push_back(this_marker);
        }
        else
        {
          ROS_WARN("GetUnlabeledMarkerGlobalTranslation failed (result = %d)",
                   (int)(_Output_GetUnlabeledMarkerGlobalTranslation.Result));

        }
      }
      markers_pub.publish(markers_msg);
    }
  }
예제 #2
0
// mocap position thread
void DataStreamClient::run(void)
{

  while (true) //TODO: exit cleanly?
  {

    // get frame
    while (_vicon_client.GetFrame().Result != Result::Success) {
      dbg("Couldn't GetFrame()\n");
      usleep(1000);
    }

    // get timecode and populate subject message
    //    Output_GetTimecode time_code = _vicon_client.GetTimecode();
    vicon::body_t msg;
    msg.utime = _timestamp_now();

    vicon::vicon_t system;

    // get subject count
    system.nummodels = _vicon_client.GetSubjectCount().SubjectCount;

    // Uh oh, models disappeared - realloc the system
    if (system.nummodels < system.models.size())
    {
        system.models.clear();
        system.models.reserve(system.nummodels);
    }

    if (system.nummodels == 0)
    {
        std::cout << "no models detected" << std::endl;
        continue;
    }

    // loop through subjects
    for (uint subject_index = 0; subject_index < system.nummodels; subject_index++) {
      ////////////////////////////////////////////////////////////////////////
      /// Marker
      vicon::model_t& model = findModel(system.models, _vicon_client.GetSubjectName(subject_index).SubjectName);

      model.nummarkers = _vicon_client.GetMarkerCount(model.name).MarkerCount;
      if (model.nummarkers < model.markers.size())
      {
        model.markers.clear();
        model.markers.reserve(model.nummarkers);
      }

      for(int32_t j = 0; j < model.nummarkers; j++)
      {
        vicon::marker_t& marker = findMarker(model.markers, _vicon_client.GetMarkerName(model.name, j).MarkerName);
        Output_GetMarkerGlobalTranslation translation = _vicon_client.GetMarkerGlobalTranslation(model.name, marker.name);
        marker.o = translation.Occluded;
        memcpy(marker.xyz, translation.Translation, 3*sizeof(double));
      }

      ////////////////////////////////////////////////////////////////////////
      /// Segments

      // get number of segments
      model.numsegments = _vicon_client.GetSegmentCount(model.name).SegmentCount;
      if (model.numsegments < model.segments.size())
      {
          model.segments.clear();
          model.segments.reserve(model.numsegments);
      }

      // get subject name
      std::string subject_name = _vicon_client.GetSubjectName(subject_index).SubjectName;

      // get root segment name
      std::string root_segment_name = _vicon_client.GetSubjectRootSegmentName(subject_name).SegmentName;

      // loop through segments
      for (uint segment_index = 0; segment_index < model.numsegments; segment_index++) {
        // get segment name
        std::string segment_name = _vicon_client.GetSegmentName(subject_name, segment_index).SegmentName;

        vicon::segment_t& segment = findSegment(model.segments, segment_name);
        Output_GetSegmentGlobalRotationEulerXYZ A = _vicon_client.GetSegmentGlobalRotationEulerXYZ(model.name, segment.name);
        Output_GetSegmentGlobalTranslation T = _vicon_client.GetSegmentGlobalTranslation(model.name, segment.name);
        Output_GetSegmentLocalRotationEulerXYZ ba = _vicon_client.GetSegmentLocalRotationEulerXYZ(model.name, segment.name);
        Output_GetSegmentLocalTranslation bt = _vicon_client.GetSegmentLocalTranslation(model.name, segment.name);
        memcpy(segment.A, A.Rotation, 3*sizeof(double));
        memcpy(segment.T, T.Translation, 3*sizeof(double));
        memcpy(segment.ba, ba.Rotation, 3*sizeof(double));
        memcpy(segment.bt, bt.Translation, 3*sizeof(double));

        // check if root segment
        if (segment_name == root_segment_name) { //TODO: handle articulated bodies
          // get segment translation
          // Output_GetSegmentStaticTranslation segment_translation = _vicon_client.GetSegmentStaticTranslation(subject_name, segment_name);
          Output_GetSegmentGlobalTranslation segment_translation = _vicon_client.GetSegmentGlobalTranslation(
              subject_name, segment_name);

          // get segment rotation
          //Output_GetSegmentStaticRotationQuaternion segment_rotation = _vicon_client.GetSegmentStaticRotationQuaternion(subject_name, segment_name);
          Output_GetSegmentGlobalRotationQuaternion segment_rotation =
              _vicon_client.GetSegmentGlobalRotationQuaternion(subject_name, segment_name);
          //           Output_GetSegmentGlobalRotationEulerXYZ   segment_rotation = _vicon_client.GetSegmentGlobalRotationEulerXYZ(subject_name, segment_name);

          // populate message with position
          for (int i = 0; i < 3; i++)
            msg.trans[i] = segment_translation.Translation[i]/1000.0; //vicon data is in mm
	  msg.quat[0] = segment_rotation.Rotation[3]; //vicon is x,y,z,w
	  msg.quat[1] = segment_rotation.Rotation[0];
	  msg.quat[2] = segment_rotation.Rotation[1];
	  msg.quat[3] = segment_rotation.Rotation[2];


          std::string channel = "VICON_" + subject_name;
          _lcm.publish(channel.c_str(), &msg);

          // break from segment for loop
          break;
        } // root segment
      } // for each segment (model.numsegments)
    } // for each subject (system.nummodels)

    _lcm.publish("VICON_MARKERS", &system);

  }

  // disconnect client
  dbg("Subject position thread terminated properly, disconnecting client\n");
  _vicon_client.Disconnect();
}