5 #include "sensor_msgs/Image.h" 6 #include "sensor_msgs/CameraInfo.h" 10 #include <boost/shared_ptr.hpp> 17 #define targetWidth 500 18 #define targetHeight 500 49 virtual void onDeviceChange(
const Controller&);
50 virtual void onServiceConnect(
const Controller&);
51 virtual void onServiceDisconnect(
const Controller&);
58 _left_node = boost::make_shared<ros::NodeHandle>(
"left");
59 _right_node = boost::make_shared<ros::NodeHandle>(
"right");
60 std::cout <<
"Initialized" << std::endl;
61 _pub_image_left = _left_node->advertise<sensor_msgs::Image>(
"image_raw", 1);
62 _pub_info_left = _left_node->advertise<sensor_msgs::CameraInfo>(
"camera_info", 1);
63 _pub_image_right = _right_node->advertise<sensor_msgs::Image>(
"image_raw", 1);
64 _pub_info_right = _right_node->advertise<sensor_msgs::CameraInfo>(
"camera_info", 1);
66 std::string default_l_info_filename;
67 std::string default_r_info_filename;
69 std::vector<std::string> search_path;
71 rp.
crawl(search_path, 1);
73 if (rp.
find(
"leap_motion",path)==
true) {
74 default_l_info_filename = path + std::string(
"/config/camera_info/leap_cal_left.yml");
75 default_r_info_filename = path + std::string(
"/config/camera_info/leap_cal_right.yml");
78 default_l_info_filename =
"";
79 default_r_info_filename =
"";
82 std::string l_info_filename;
83 std::string r_info_filename;
84 local_nh.
param(
"template_filename_left", l_info_filename, default_l_info_filename);
85 local_nh.
param(
"template_filename_right", r_info_filename, default_r_info_filename);
86 l_info_filename = std::string(
"file://") + l_info_filename;
87 r_info_filename = std::string(
"file://") + r_info_filename;
93 std::cout <<
"Connected" << std::endl;
102 std::cout <<
"Disconnected" << std::endl;
106 std::cout <<
"Exited" << std::endl;
114 sensor_msgs::Image image_msg;
115 image_msg.header.seq = seq++;
117 image_msg.encoding =
"mono8";
118 image_msg.is_bigendian = 0;
119 for(
int camera_num=0; camera_num<2; camera_num++){
120 Image image = images[camera_num];
125 #pragma omp parallel for 132 if(pixel.
x >= 0 && pixel.
x < image.
width() && pixel.
y >= 0 && pixel.
y < image.
height()) {
133 int data_index = floor(pixel.
y) * image.
width() + floor(pixel.
x);
134 image_msg.data[cutWidth*j+i] = image.
data()[data_index];
136 image_msg.data[cutWidth*j+i] = 0;
141 sensor_msgs::CameraInfoPtr info_msg(
new sensor_msgs::CameraInfo(info_mgr_left->getCameraInfo()));
142 image_msg.header.frame_id = info_msg->header.frame_id =
"leap_optical_frame";
143 info_msg->width = image_msg.width;
144 info_msg->height = image_msg.height;
145 info_msg->header.stamp = image_msg.header.stamp;
146 info_msg->header.seq = image_msg.header.seq;
147 _pub_image_left.publish(image_msg);
148 _pub_info_left.publish(*info_msg);
150 sensor_msgs::CameraInfoPtr info_msg(
new sensor_msgs::CameraInfo(info_mgr_right->getCameraInfo()));
151 image_msg.header.frame_id = info_msg->header.frame_id =
"leap_optical_frame";
152 info_msg->width = image_msg.width;
153 info_msg->height = image_msg.height;
154 info_msg->header.stamp = image_msg.header.stamp;
155 info_msg->header.seq = image_msg.header.seq;
156 _pub_image_right.publish(image_msg);
157 _pub_info_right.publish(*info_msg);
178 std::cout <<
"Focus Gained" << std::endl;
182 std::cout <<
"Focus Lost" << std::endl;
186 std::cout <<
"Device Changed" << std::endl;
189 for (
int i = 0; i < devices.
count(); ++i) {
190 std::cout <<
"id: " << devices[i].toString() << std::endl;
191 std::cout <<
" isStreaming: " << (devices[i].isStreaming() ?
"true" :
"false") << std::endl;
196 std::cout <<
"Service Connected" << std::endl;
200 std::cout <<
"Service Disconnected" << std::endl;
203 int main(
int argc,
char** argv) {
LEAP_EXPORT void setPolicyFlags(PolicyFlag flags) const
camera_info_manager::CameraInfoManager * info_mgr_right
LEAP_EXPORT void enableGesture(Gesture::Type type, bool enable=true) const
LEAP_EXPORT bool addListener(Listener &listener)
virtual void onFrame(const Controller &)
virtual void onExit(const Controller &)
virtual void onDeviceChange(const Controller &)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
virtual void onInit(const Controller &)
virtual void onServiceDisconnect(const Controller &)
ROSCPP_DECL void spin(Spinner &spinner)
LEAP_EXPORT Vector warp(const Vector &xy) const
ros::Publisher _pub_image_left
ros::Publisher _pub_image_right
LEAP_EXPORT float rayScaleX() const
ros::Publisher _pub_info_right
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
LEAP_EXPORT float rayOffsetY() const
int main(int argc, char **argv)
boost::shared_ptr< ros::NodeHandle > _right_node
bool getSearchPathFromEnv(std::vector< std::string > &sp)
boost::shared_ptr< ros::NodeHandle > _left_node
LEAP_EXPORT int count() const
ros::Publisher _pub_info_left
void crawl(std::vector< std::string > search_path, bool force)
virtual void onFocusGained(const Controller &)
bool find(const std::string &name, std::string &path)
LEAP_EXPORT bool removeListener(Listener &listener)
virtual void onConnect(const Controller &)
LEAP_EXPORT float rayOffsetX() const
LEAP_EXPORT Frame frame(int history=0) const
virtual void onServiceConnect(const Controller &)
LEAP_EXPORT float rayScaleY() const
virtual void onFocusLost(const Controller &)
virtual void onDisconnect(const Controller &)
camera_info_manager::CameraInfoManager * info_mgr_left