hrplib/hrpModel/Sensor.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, AIST, the University of Tokyo and General Robotix Inc.
3  * All rights reserved. This program is made available under the terms of the
4  * Eclipse Public License v1.0 which accompanies this distribution, and is
5  * available at http://www.eclipse.org/legal/epl-v10.html
6  * Contributors:
7  * National Institute of Advanced Industrial Science and Technology (AIST)
8  */
14 #ifndef HRPMODEL_SENSOR_H_INCLUDED
15 #define HRPMODEL_SENSOR_H_INCLUDED
16 
17 #include <string>
18 #include <iostream>
19 #include <vector>
20 #include <hrpUtil/Eigen3d.h>
21 #include "Config.h"
22 
23 namespace hrp {
24 
25  class Link;
26 
27  class HRPMODEL_API Sensor
28  {
29  public:
30 
31  enum SensorType {
32  COMMON = 0,
41  NUM_SENSOR_TYPES
42  };
43 
44  static const int TYPE = COMMON;
45 
46  Sensor();
47  virtual ~Sensor();
48 
49  static Sensor* create(int type);
50  static void destroy(Sensor* sensor);
51 
52  virtual void operator=(const Sensor& org);
53 
54  virtual void clear();
55 
56  std::string name;
57  int type;
58  int id;
62 
63  virtual void putInformation(std::ostream& os);
64 
65  };
66 
67 
68  class HRPMODEL_API ForceSensor : public Sensor
69  {
70  public:
71  static const int TYPE = FORCE;
72 
73  ForceSensor();
76 
77  virtual void clear();
78  virtual void putInformation(std::ostream& os);
79  };
80 
81 
82  class HRPMODEL_API RateGyroSensor : public Sensor
83  {
84  public:
85  static const int TYPE = RATE_GYRO;
86 
89 
90  virtual void clear();
91  virtual void putInformation(std::ostream& os);
92  };
93 
94 
95  class HRPMODEL_API AccelSensor : public Sensor
96  {
97  public:
98  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
99 
100  static const int TYPE = ACCELERATION;
101 
102  AccelSensor();
103 
105 
106  virtual void clear();
107  virtual void putInformation(std::ostream& os);
108 
109  // The following members are used in the ForwardDynamics class
110  typedef Eigen::Vector2d vector2;
111  vector2 x[3];
113  };
114 
115  class HRPMODEL_API RangeSensor : public Sensor
116  {
117  public:
118  static const int TYPE = RANGE;
119 
120  RangeSensor();
121 
122  double scanAngle, scanStep, scanRate, maxDistance;
123  std::vector<double> distances;
125  bool isUpdated, isEnabled;
126  };
127 
128 #ifdef far
129 #undef far
130 #endif
131 #ifdef near
132 #undef near
133 #endif
134 
135  class HRPMODEL_API VisionSensor : public Sensor
136  {
137  public:
138  typedef enum {NONE, COLOR, MONO, DEPTH, COLOR_DEPTH, MONO_DEPTH} ImageType;
139  static const int TYPE = VISION;
140 
141  VisionSensor();
142  int width, height;
143  double far, near, fovy, frameRate;
145  std::vector<unsigned char> image;
146  std::vector<unsigned char> depth;
148  bool isUpdated, isEnabled;
149  };
150 };
151 
152 
153 #endif
hrp::VisionSensor::depth
std::vector< unsigned char > depth
Definition: hrplib/hrpModel/Sensor.h:146
hrp::Sensor::localR
Matrix33 localR
Definition: hrplib/hrpModel/Sensor.h:60
hrp::VisionSensor
Definition: hrplib/hrpModel/Sensor.h:135
hrp::VisionSensor::imageType
ImageType imageType
Definition: hrplib/hrpModel/Sensor.h:144
hrp::VisionSensor::near
double near
Definition: hrplib/hrpModel/Sensor.h:143
hrp::RangeSensor::distances
std::vector< double > distances
Definition: hrplib/hrpModel/Sensor.h:123
hrp::Sensor::type
int type
Definition: hrplib/hrpModel/Sensor.h:57
hrp
Definition: ColdetModel.h:28
hrp::ForceSensor::f
Vector3 f
Definition: hrplib/hrpModel/Sensor.h:74
hrp::ForceSensor
Definition: hrplib/hrpModel/Sensor.h:68
create
static BodyCustomizerHandle create(BodyHandle bodyHandle, const char *modelName)
Definition: bush_customizer.cpp:126
hrp::Sensor::RATE_GYRO
@ RATE_GYRO
Definition: hrplib/hrpModel/Sensor.h:34
destroy
int destroy(gz_stream *s)
Definition: gzio.c:355
type
png_infop png_charp png_int_32 png_int_32 int * type
Definition: png.h:2330
hrp::Sensor::link
Link * link
Definition: hrplib/hrpModel/Sensor.h:59
hrp::ForceSensor::tau
Vector3 tau
Definition: hrplib/hrpModel/Sensor.h:75
hrp::Vector3
Eigen::Vector3d Vector3
Definition: EigenTypes.h:11
hrp::Sensor::TORQUE
@ TORQUE
Definition: hrplib/hrpModel/Sensor.h:39
hrp::Sensor::SensorType
SensorType
Definition: hrplib/hrpModel/Sensor.h:31
hrp::Sensor::name
std::string name
Definition: hrplib/hrpModel/Sensor.h:56
hrp::Sensor::localPos
Vector3 localPos
Definition: hrplib/hrpModel/Sensor.h:61
hrp::VisionSensor::NONE
@ NONE
Definition: hrplib/hrpModel/Sensor.h:138
hrp::RangeSensor
Definition: hrplib/hrpModel/Sensor.h:115
hrp::RateGyroSensor::w
Vector3 w
Definition: hrplib/hrpModel/Sensor.h:88
hrp::AccelSensor
Definition: hrplib/hrpModel/Sensor.h:95
hrp::Sensor::VISION
@ VISION
Definition: hrplib/hrpModel/Sensor.h:38
hrp::RangeSensor::isUpdated
bool isUpdated
Definition: hrplib/hrpModel/Sensor.h:125
TYPE
@ TYPE
Definition: inflate.h:32
hrp::Sensor::RANGE
@ RANGE
Definition: hrplib/hrpModel/Sensor.h:40
hrp::Sensor::ACCELERATION
@ ACCELERATION
Definition: hrplib/hrpModel/Sensor.h:35
hrp::Sensor::FORCE
@ FORCE
Definition: hrplib/hrpModel/Sensor.h:33
hrp::VisionSensor::ImageType
ImageType
Definition: hrplib/hrpModel/Sensor.h:138
hrp::RangeSensor::scanStep
double scanStep
Definition: hrplib/hrpModel/Sensor.h:122
hrp::VisionSensor::image
std::vector< unsigned char > image
Definition: hrplib/hrpModel/Sensor.h:145
hrp::VisionSensor::isUpdated
bool isUpdated
Definition: hrplib/hrpModel/Sensor.h:148
hrp::VisionSensor::nextUpdateTime
double nextUpdateTime
Definition: hrplib/hrpModel/Sensor.h:147
hrp::Sensor
Definition: hrplib/hrpModel/Sensor.h:27
hrp::Matrix33
Eigen::Matrix3d Matrix33
Definition: EigenTypes.h:12
hrp::Sensor::PRESSURE
@ PRESSURE
Definition: hrplib/hrpModel/Sensor.h:36
Eigen3d.h
hrp::Sensor::id
int id
Definition: hrplib/hrpModel/Sensor.h:58
height
png_infop png_uint_32 png_uint_32 * height
Definition: png.h:2306
hrp::Sensor::PHOTO_INTERRUPTER
@ PHOTO_INTERRUPTER
Definition: hrplib/hrpModel/Sensor.h:37
hrp::AccelSensor::isFirstUpdate
bool isFirstUpdate
Definition: hrplib/hrpModel/Sensor.h:112
hrp::VisionSensor::width
int width
Definition: hrplib/hrpModel/Sensor.h:142
hrp::RateGyroSensor
Definition: hrplib/hrpModel/Sensor.h:82
hrp::RangeSensor::nextUpdateTime
double nextUpdateTime
Definition: hrplib/hrpModel/Sensor.h:124
hrp::AccelSensor::dv
Vector3 dv
Definition: hrplib/hrpModel/Sensor.h:104
hrp::AccelSensor::vector2
Eigen::Vector2d vector2
Definition: hrplib/hrpModel/Sensor.h:110


openhrp3
Author(s): AIST, General Robotix Inc., Nakamura Lab of Dept. of Mechano Informatics at University of Tokyo
autogenerated on Wed Sep 7 2022 02:51:04