joint_imager.h
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 #ifndef LASER_JOINT_PROCESSOR_JOINT_IMAGER_H_
36 #define LASER_JOINT_PROCESSOR_JOINT_IMAGER_H_
37 
38 #include <opencv2/core/core.hpp>
41 #include <calibration_msgs/DenseLaserSnapshot.h>
42 
43 namespace laser_joint_processor
44 {
45 
47 {
48 public:
49  JointImager();
50  ~JointImager();
51 
52  bool update(const calibration_msgs::DenseLaserSnapshot& snapshot,
54  const ros::Duration& max_interp = ros::Duration(.25));
55 
56  void displayImage(unsigned int i);
57  void writeImage(unsigned int i, const std::string& filename);
58  cv::Mat_<cv::Vec2f> getJointImage(unsigned int index) const;
59 
60 protected:
61  std::vector<cv::Mat_<cv::Vec2f> > images;
62 
63  bool interpPosition(const ros::Time& target,
65  std::vector<double>& result);
66 
67  bool computeVelocity(const ros::Time& start, const ros::Time& end,
69  std::vector<double>& result);
70 
71  void allocateImages(unsigned int height, unsigned int width, unsigned int channels);
72 
73 };
74 
75 }
76 
77 
78 #endif
79 
filename
bool computeVelocity(const ros::Time &start, const ros::Time &end, const settlerlib::SortedDeque< joint_states_settler::DeflatedJointStates > &cache, std::vector< double > &result)
void allocateImages(unsigned int height, unsigned int width, unsigned int channels)
void writeImage(unsigned int i, const std::string &filename)
bool update(const calibration_msgs::DenseLaserSnapshot &snapshot, const settlerlib::SortedDeque< joint_states_settler::DeflatedJointStates > &cache, const ros::Duration &max_interp=ros::Duration(.25))
bool interpPosition(const ros::Time &target, const settlerlib::SortedDeque< joint_states_settler::DeflatedJointStates > &cache, std::vector< double > &result)
cv::Mat_< cv::Vec2f > getJointImage(unsigned int index) const
std::vector< cv::Mat_< cv::Vec2f > > images
Definition: joint_imager.h:61


laser_joint_processor
Author(s): Vijay Pradeep
autogenerated on Tue Jun 1 2021 02:50:55