#include "ros/ros.h"#include "visualization_msgs/Marker.h"#include "visualization_msgs/MarkerArray.h"#include "leap_motion/Human.h"#include "leap_motion/Hand.h"#include "leap_motion/Finger.h"#include "leap_motion/Bone.h"#include "Leap.h"#include <iostream>
Go to the source code of this file.
Functions | |
| visualization_msgs::Marker | createFingerLines (const leap_motion::Human::ConstPtr &human, std::string hand_ns, std::string finger_ns, unsigned int id, leap_motion::Bone current_bone) |
| Adds lines between the tips of the bones. | |
| visualization_msgs::Marker | createHandOutline (const leap_motion::Human::ConstPtr &human, std::string hand_ns, unsigned int id, leap_motion::Hand current_hand) |
| Creates a representation of palm. | |
| visualization_msgs::Marker | createJointMarker (const leap_motion::Human::ConstPtr &human, std::string hand_ns, std::string finger_ns, unsigned int id, geometry_msgs::Pose location) |
| Adds circles at the intersection of bones. | |
| visualization_msgs::Marker | createPalmPosition (const leap_motion::Human::ConstPtr &human, std::string hand_ns, unsigned int id, geometry_msgs::Point centre_point) |
| Represents the midpoint of the palm. | |
| void | createVisualization (visualization_msgs::MarkerArray *marker_array, const leap_motion::Human::ConstPtr &human, leap_motion::Hand hand, std::string hand_ns, uint8_t hand_id) |
| Creates a visualization of an entire hand from he wrist up. | |
| void | frameCallback (const leap_motion::Human::ConstPtr &human) |
| Called when a new Human.msg is received. | |
| int | main (int argc, char **argv) |
Variables | |
| const std::string | fingerNames [] = {"Thumb", "Index", "Middle", "Ring", "Pinky"} |
| static ros::Publisher * | marker_pub |
| visualization_msgs::Marker createFingerLines | ( | const leap_motion::Human::ConstPtr & | human, |
| std::string | hand_ns, | ||
| std::string | finger_ns, | ||
| unsigned int | id, | ||
| leap_motion::Bone | current_bone | ||
| ) |
Adds lines between the tips of the bones.
Takes a pointer to human.msg, and a bone.msg. Using that information adds lines between the tips of the bones.
| human | Pointer to the received Human.msg |
| hand_ns | Used to create a unique namespace |
| finger_ns | Used to create a unique namespace |
| current_bone | The bone that will be represented as a line. |
Definition at line 68 of file lmc_visualizer_node.cpp.
| visualization_msgs::Marker createHandOutline | ( | const leap_motion::Human::ConstPtr & | human, |
| std::string | hand_ns, | ||
| unsigned int | id, | ||
| leap_motion::Hand | current_hand | ||
| ) |
Creates a representation of palm.
Takes a pointer to human.msg, and a hand.msg. Using that information adds draw lines between fingers to create a palm.
| human | Pointer to the received Human.msg |
| hand_ns | Used to create a unique namespace |
| finger_ns | Used to create a unique namespace |
| current_hand | The hand from which the palm will be created |
Definition at line 113 of file lmc_visualizer_node.cpp.
| visualization_msgs::Marker createJointMarker | ( | const leap_motion::Human::ConstPtr & | human, |
| std::string | hand_ns, | ||
| std::string | finger_ns, | ||
| unsigned int | id, | ||
| geometry_msgs::Pose | location | ||
| ) |
Adds circles at the intersection of bones.
Takes a pointer to human.msg, and a start of a bone. Using that information creates a sphere visualization marker that will later be appended to a marker array.
| human | Pointer to the received Human.msg |
| hand_ns | Used to create a unique namespace |
| finger_ns | Used to create a unique namespace |
| location | Tip position of a bone object |
Definition at line 27 of file lmc_visualizer_node.cpp.
| visualization_msgs::Marker createPalmPosition | ( | const leap_motion::Human::ConstPtr & | human, |
| std::string | hand_ns, | ||
| unsigned int | id, | ||
| geometry_msgs::Point | centre_point | ||
| ) |
Represents the midpoint of the palm.
Takes a pointer to human.msg, and pose the the centre point of the palm. Using that information creates a sphere at that location.
| human | Pointer to a received Human.msg |
| hand_ns | Used to create a unique namespace |
| id | A unique id to the created marker |
| centre_point | The palm centre of a hand |
Definition at line 216 of file lmc_visualizer_node.cpp.
| void createVisualization | ( | visualization_msgs::MarkerArray * | marker_array, |
| const leap_motion::Human::ConstPtr & | human, | ||
| leap_motion::Hand | hand, | ||
| std::string | hand_ns, | ||
| uint8_t | hand_id | ||
| ) |
Creates a visualization of an entire hand from he wrist up.
Using the given information calls out different functions to create a visualization of a detected hand for displaying in Rviz.
| marker_array | An array into which all created markers will be added |
| human | Pointer to a received Human.msg |
| hand | A hand.msg from which the hand visualization will be created. |
| hand_ns | Used to create a unique namespace |
| hand_id | A unique id to the create markers |
Definition at line 259 of file lmc_visualizer_node.cpp.
| void frameCallback | ( | const leap_motion::Human::ConstPtr & | human | ) |
Called when a new Human.msg is received.
| human | Pointer to thr received Human.msg |
Definition at line 301 of file lmc_visualizer_node.cpp.
| int main | ( | int | argc, |
| char ** | argv | ||
| ) |
Definition at line 321 of file lmc_visualizer_node.cpp.
| const std::string fingerNames[] = {"Thumb", "Index", "Middle", "Ring", "Pinky"} |
Definition at line 14 of file lmc_visualizer_node.cpp.
ros::Publisher* marker_pub [static] |
Definition at line 13 of file lmc_visualizer_node.cpp.