white_balance_converter.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
3 #include <sensor_msgs/Image.h>
4 #include <sensor_msgs/PointCloud2.h>
5 
6 #include <Eigen/Dense>
7 
8 #include "jsk_perception/WhiteBalance.h"
9 #include "jsk_perception/WhiteBalancePoints.h"
10 
12 
13 private:
15 
18 
19  double cmat[12]; // convert_matrix
20  double pmat[48]; // paramteter matrix
21  //param
23 
24  typedef union
25  {
26  struct /*anonymous*/
27  {
28  unsigned char Blue; // Blue channel
29  unsigned char Green; // Green channel
30  unsigned char Red; // Red channel
31  unsigned char Alpha;
32  };
33  float float_value;
34  long long_value;
35  } RGBValue;
36 
37 public:
38  WhiteBalanceConverter() : nh_ () {
39  ros::NodeHandle pnh("~");
40 
41  if (pnh.hasParam("parameter_matrix")) {
42  XmlRpc::XmlRpcValue param_val;
43  pnh.getParam("parameter_matrix", param_val);
44  // ROS_INFO("MATRIX %d", param_val.size());
45  if (param_val.getType() == XmlRpc::XmlRpcValue::TypeArray && param_val.size() == 48) {
46  for ( int i = 0; i < 48; i++) {
47  pmat[i] = param_val[i];
48  }
49  }
50  for ( int i = 0; i < 12; i++ ) {
51  ROS_INFO("[%f, %f, %f, %f]", pmat[4*i + 0], pmat[4*i + 1], pmat[4*i + 2], pmat[4*i + 3]);
52  }
53  }
54 
55  service_img_ = pnh.advertiseService(pnh.resolveName("convert_image"),
57  service_pts_ = pnh.advertiseService(pnh.resolveName("convert_points"),
59  }
60 
61  bool imageCallback(jsk_perception::WhiteBalance::Request &req,
62  jsk_perception::WhiteBalance::Response &res) {
63  makeConvertMatrix(req.reference_color[0], req.reference_color[1], req.reference_color[2]);
64 
65  return true;
66  }
67 
68  bool pointsCallback(jsk_perception::WhiteBalancePoints::Request &req,
69  jsk_perception::WhiteBalancePoints::Response &res) {
70  makeConvertMatrix(req.reference_color[0], req.reference_color[1], req.reference_color[2]);
71 
72  int rgb_offset = -1;
73  for (size_t i = 0; i < req.input.fields.size(); i++) {
74  if ( req.input.fields[i].name == "rgb" ) {
75  rgb_offset = req.input.fields[i].offset;
76  break;
77  }
78  }
79  //ROS_INFO("offst = %d", rgb_offset);
80 
81  if ( rgb_offset < 0 ) {
82  ROS_WARN("point cloud didn't have rgb field");
83  return false;
84  }
85 
86  res.output = req.input;
87  int size = req.input.height * req.input.width;
88  int step = req.input.point_step;
89  unsigned char *sdata = (unsigned char *) &(req.input.data[0]);
90  unsigned char *ddata = (unsigned char *) &(res.output.data[0]);
91 
92  for(int i = 0; i < size; i++, sdata += step, ddata += step) {
93  RGBValue rgb;
94  rgb.float_value = *((float *)(sdata + rgb_offset));
95  int r = rgb.Red; int g = rgb.Green; int b = rgb.Blue;
96  convertColor(r, g, b);
97  rgb.long_value = 0;
98  rgb.Red = (unsigned char)r;
99  rgb.Green = (unsigned char)g;
100  rgb.Blue = (unsigned char)b;
101  *((float *)(ddata + rgb_offset)) = rgb.float_value;
102  }
103 
104  return true;
105  }
106 
107  inline void convertColor (int &r, int &g, int &b) {
108  double rr = ( cmat[0] * r ) + ( cmat[1] * g ) + ( cmat[2] * b ) + cmat[3]*256;
109  double gg = ( cmat[4] * r ) + ( cmat[5] * g ) + ( cmat[6] * b ) + cmat[7]*256;
110  double bb = ( cmat[8] * r ) + ( cmat[9] * g ) + ( cmat[10] * b ) + cmat[11]*256;
111 
112  r = round(rr);
113  g = round(gg);
114  b = round(bb);
115 
116  if(r > 255) r = 255; if (r < 0) r = 0;
117  if(g > 255) g = 255; if (g < 0) g = 0;
118  if(b > 255) b = 255; if (b < 0) b = 0;
119  }
120 
121  void makeConvertMatrix(float refr, float refg, float refb) {
122  for(int i = 0; i < 12; i++) {
123  cmat[i] =
124  ( pmat[4*i + 0] * refr ) +
125  ( pmat[4*i + 1] * refg ) +
126  ( pmat[4*i + 2] * refb ) +
127  pmat[4*i + 3] ;
128  }
129  ROS_INFO("%f %f %f %f", cmat[0], cmat[1], cmat[2], cmat[3]);
130  ROS_INFO("%f %f %f %f", cmat[4], cmat[5], cmat[6], cmat[7]);
131  ROS_INFO("%f %f %f %f", cmat[8], cmat[9], cmat[10], cmat[11]);
132 
133  Eigen::Matrix4d mat;
134  mat(0,0) = cmat[0]; mat(0,1) = cmat[1]; mat(0,2) = cmat[2]; mat(0,3) = cmat[3];
135  mat(1,0) = cmat[4]; mat(1,1) = cmat[5]; mat(1,2) = cmat[6]; mat(1,3) = cmat[7];
136  mat(2,0) = cmat[8]; mat(2,1) = cmat[9]; mat(2,2) = cmat[10]; mat(2,3) = cmat[11];
137  mat(3,0) = 0.0; mat(3,1) = 0.0; mat(3,2) = 0.0; mat(3,3) = 1.0;
138 
139  Eigen::Matrix4d imat = mat.inverse();
140  cmat[0] = imat(0, 0); cmat[1] = imat(0, 1); cmat[2] = imat(0, 2); cmat[3] = imat(0, 3);
141  cmat[4] = imat(1, 0); cmat[5] = imat(1, 1); cmat[6] = imat(1, 2); cmat[7] = imat(1, 3);
142  cmat[8] = imat(2, 0); cmat[9] = imat(2, 1); cmat[10] = imat(2, 2); cmat[11] = imat(2, 3);
143 
144  ROS_INFO("%f %f %f %f", cmat[0], cmat[1], cmat[2], cmat[3]);
145  ROS_INFO("%f %f %f %f", cmat[4], cmat[5], cmat[6], cmat[7]);
146  ROS_INFO("%f %f %f %f", cmat[8], cmat[9], cmat[10], cmat[11]);
147  }
148 };
149 
150 int main (int argc, char** argv)
151 {
152  // ROS init
153  ros::init (argc, argv, "white_balance_converter");
154 
156  ros::spin ();
157 
158  return (0);
159 }
int size() const
std::string resolveName(const std::string &name, bool remap=true) const
bool imageCallback(jsk_perception::WhiteBalance::Request &req, jsk_perception::WhiteBalance::Response &res)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
Type const & getType() const
#define ROS_WARN(...)
int main(int argc, char **argv)
ROSCPP_DECL void spin(Spinner &spinner)
#define ROS_INFO(...)
void makeConvertMatrix(float refr, float refg, float refb)
void convertColor(int &r, int &g, int &b)
bool pointsCallback(jsk_perception::WhiteBalancePoints::Request &req, jsk_perception::WhiteBalancePoints::Response &res)
unsigned int step
bool getParam(const std::string &key, std::string &s) const
r
bool hasParam(const std::string &key) const
g


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Mon May 3 2021 03:03:27