5 #include "visualization_msgs/MarkerArray.h" 6 #include "geometry_msgs/PoseStamped.h" 30 virtual void onDeviceChange(
const Controller&);
31 virtual void onServiceConnect(
const Controller&);
32 virtual void onServiceDisconnect(
const Controller&);
37 std::cout <<
"Initialized" << std::endl;
38 _pub_marker_array = _node.advertise<visualization_msgs::MarkerArray>(
"hands", 1);
39 _pub_bone_only = _node.advertise<visualization_msgs::Marker>(
"hands_line", 1);
44 std::cout <<
"Connected" << std::endl;
53 std::cout <<
"Disconnected" << std::endl;
57 std::cout <<
"Exited" << std::endl;
64 visualization_msgs::Marker marker_msg, joint_msg;
65 visualization_msgs::MarkerArray marker_array_msg;
66 marker_msg.header.frame_id=joint_msg.header.frame_id=
"/leap_optical_frame";
68 marker_msg.ns=
"leap_marker";
72 marker_msg.type = visualization_msgs::Marker::LINE_LIST;
73 joint_msg.type = visualization_msgs::Marker::SPHERE;
74 marker_msg.scale.x = 0.005;
75 joint_msg.scale.x = joint_msg.scale.y = joint_msg.scale.z = 0.015;
76 joint_msg.color.r = .0f;
77 joint_msg.color.g = 1.0f;
78 joint_msg.color.b = 1.0f;
79 joint_msg.color.a = 0.7f;
80 marker_msg.action = joint_msg.action = visualization_msgs::Marker::ADD;
81 marker_msg.lifetime = joint_msg.lifetime =
ros::Duration(0.1);
86 const Hand hand = *hl;
93 for (
int b = 0; b < 4; ++b) {
96 geometry_msgs::Point point;
100 marker_msg.points.push_back(point);
101 point.x = joint_msg.pose.position.x = -bone.
nextJoint().
x/1000;
102 point.y = joint_msg.pose.position.y = bone.
nextJoint().
z/1000;
103 point.z = joint_msg.pose.position.z = bone.
nextJoint().
y/1000;
104 marker_msg.points.push_back(point);
105 joint_msg.id = joint_msg.id+1;
106 marker_array_msg.markers.push_back(joint_msg);
107 std_msgs::ColorRGBA color;
108 color.r = 1.0f; color.g=.0f; color.b=.0f, color.a=1.0f;
109 marker_msg.colors.push_back(color);
110 marker_msg.colors.push_back(color);
114 _pub_marker_array.publish(marker_array_msg);
115 _pub_bone_only.publish(marker_msg);
119 std::cout <<
"Focus Gained" << std::endl;
123 std::cout <<
"Focus Lost" << std::endl;
127 std::cout <<
"Device Changed" << std::endl;
130 for (
int i = 0; i < devices.
count(); ++i) {
131 std::cout <<
"id: " << devices[i].toString() << std::endl;
132 std::cout <<
" isStreaming: " << (devices[i].isStreaming() ?
"true" :
"false") << std::endl;
137 std::cout <<
"Service Connected" << std::endl;
141 std::cout <<
"Service Disconnected" << std::endl;
144 int main(
int argc,
char** argv) {
ros::Publisher _pub_bone_only
LEAP_EXPORT void setPolicyFlags(PolicyFlag flags) const
LEAP_EXPORT void enableGesture(Gesture::Type type, bool enable=true) const
LEAP_EXPORT const_iterator begin() const
virtual void onServiceConnect(const Controller &)
LEAP_EXPORT bool addListener(Listener &listener)
virtual void onExit(const Controller &)
virtual void onFocusLost(const Controller &)
LEAP_EXPORT Vector prevJoint() const
LEAP_EXPORT const_iterator end() const
LEAP_EXPORT const_iterator begin() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
LEAP_EXPORT Vector nextJoint() const
virtual void onInit(const Controller &)
ROSCPP_DECL void spin(Spinner &spinner)
virtual void onServiceDisconnect(const Controller &)
LEAP_EXPORT Bone bone(Bone::Type boneIx) const
LEAP_EXPORT const_iterator end() const
std::vector< std::vector< lpf > > hands
ros::Publisher _pub_marker_array
virtual void onDeviceChange(const Controller &)
LEAP_EXPORT int count() const
virtual void onConnect(const Controller &)
int main(int argc, char **argv)
virtual void onDisconnect(const Controller &)
LEAP_EXPORT bool removeListener(Listener &listener)
LEAP_EXPORT Frame frame(int history=0) const
virtual void onFocusGained(const Controller &)
virtual void onFrame(const Controller &)