23 #include <tuw_artoolkitplus/TransformArrayStamped.h> 25 int main(
int argc,
char **argv) {
34 tf::Matrix3x3 R(M[0][0], M[0][1], M[0][2], M[1][0], M[1][1], M[1][2], M[2][0], M[2][1], M[2][2]);
50 marker_msgs::MarkerDetection msg;
55 msg.distance_max_id = 5;
56 msg.view_direction.x = 0;
57 msg.view_direction.y = 0;
58 msg.view_direction.z = 0;
59 msg.view_direction.w = 1;
60 msg.fov_horizontal = 6;
63 msg.markers = marker_msgs::MarkerDetection::_markers_type();
69 marker_msgs::Marker marker;
73 marker.ids_confidence.resize(1);
75 marker.ids_confidence[0] = 1;
78 msg.markers.push_back(marker);
86 tuw_artoolkitplus::TransformArrayStamped msg;
93 geometry_msgs::Vector3 &desT = msg.transform[i].translation;
94 geometry_msgs::Quaternion &desQ = msg.transform[i].rotation;
97 desT.x = srcT.
x(), desT.y = srcT.
y(), desT.z = srcT.
z();
98 desQ.x = srcQ.x(), desQ.y = srcQ.y(), desQ.z = srcQ.z(), desQ.w = srcQ.w();
99 msg.child_frame_id[i] = it->child_frame_id_;
106 ((tuw_artoolkitplus::ARParamConfig&)
param_) = config;
void publish(const boost::shared_ptr< M > &message) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void getRotation(Quaternion &q) const
TFSIMD_FORCE_INLINE const tfScalar & x() const
TFSIMD_FORCE_INLINE const tfScalar & z() const
TFSIMD_FORCE_INLINE const tfScalar & y() const
uint32_t getNumSubscribers() const
static void poseTFToMsg(const Pose &bt, geometry_msgs::Pose &msg)