Skip to content

Commit

Permalink
sensor refactoring
Browse files Browse the repository at this point in the history
moved Camera and Ray sensor classes into own headers
  • Loading branch information
rhaschke committed Sep 7, 2018
1 parent 635f582 commit ec55e6b
Show file tree
Hide file tree
Showing 3 changed files with 130 additions and 110 deletions.
79 changes: 79 additions & 0 deletions urdf_sensor/include/urdf_sensor/camera.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,79 @@
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2008, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the Willow Garage nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/

/* Author: John Hsu */

/* example
<sensor name="my_camera_sensor" update_rate="20">
<origin xyz="0 0 0" rpy="0 0 0"/>
<camera>
<horizontal_hov>1.5708</horizontal_hov>
<image width="640" height="480" format="R8G8B8"/>
<clip near="0.01" far="50.0"/>
</camera>
</sensor>
*/

#ifndef URDF_SENSOR_CAMERA_H
#define URDF_SENSOR_CAMERA_H

namespace urdf {

class Camera : public SensorBase
{
public:
Camera() { this->clear(); };
unsigned int width, height;
/// format is optional: defaults to R8G8B8), but can be
/// (L8|R8G8B8|B8G8R8|BAYER_RGGB8|BAYER_BGGR8|BAYER_GBRG8|BAYER_GRBG8)
std::string format;
double hfov;
double near;
double far;

void clear()
{
hfov = 0;
width = 0;
height = 0;
format.clear();
near = 0;
far = 0;
}
};

}
#endif
Original file line number Diff line number Diff line change
Expand Up @@ -36,14 +36,6 @@

/* example
<sensor name="my_camera_sensor" update_rate="20">
<origin xyz="0 0 0" rpy="0 0 0"/>
<camera>
<horizontal_hov>1.5708</horizontal_hov>
<image width="640" height="480" format="R8G8B8"/>
<clip near="0.01" far="50.0"/>
</camera>
</sensor>
<sensor name="my_ray_sensor" update_rate="20">
<origin xyz="0 0 0" rpy="0 0 0"/>
<ray>
Expand All @@ -56,63 +48,12 @@
*/

#ifndef URDF_SENSOR_RAY_H
#define URDF_SENSOR_RAY_H

namespace urdf {

#ifndef URDF_SENSOR_H
#define URDF_SENSOR_H

#include <string>
#include <vector>
#include <map>
#include "urdf_model/pose.h"
#include "urdf_model/joint.h"
#include "urdf_model/link.h"
#include "urdf_model/types.h"
#include "urdf_sensor/types.h"

namespace urdf{

class SensorBase {
public:
enum {VISUAL, FORCE, TACTILE, IMU, GYRO, ACCELERATION, GPS} sensor_type;
virtual ~SensorBase(void)
{
}
};

class VisualSensor : public SensorBase
{
public:
enum {CAMERA, RAY, DEPTH} type;
virtual ~VisualSensor(void)
{
}
};

class Camera : public VisualSensor
{
public:
Camera() { this->clear(); };
unsigned int width, height;
/// format is optional: defaults to R8G8B8), but can be
/// (L8|R8G8B8|B8G8R8|BAYER_RGGB8|BAYER_BGGR8|BAYER_GBRG8|BAYER_GRBG8)
std::string format;
double hfov;
double near;
double far;

void clear()
{
hfov = 0;
width = 0;
height = 0;
format.clear();
near = 0;
far = 0;
};
};

class Ray : public VisualSensor
class Ray : public SensorBase
{
public:
Ray() { this->clear(); };
Expand All @@ -136,48 +77,8 @@ class Ray : public VisualSensor
vertical_resolution = 1;
vertical_min_angle = 0;
vertical_max_angle = 0;
};
}
};


class Sensor
{
public:
Sensor() { this->clear(); };

/// sensor name must be unique
std::string name;

/// update rate in Hz
double update_rate;

/// transform from parent frame to optical center
/// with z-forward and x-right, y-down
Pose origin;

/// sensor
SensorBaseSharedPtr sensor;

/// Parent link element name. A pointer is stored in parent_link_.
std::string parent_link_name;

LinkSharedPtr getParent() const
{return parent_link_.lock();};

void setParent(LinkSharedPtr parent)
{ this->parent_link_ = parent; }

void clear()
{
this->name.clear();
this->sensor.reset();
this->parent_link_name.clear();
this->parent_link_.reset();
};

private:
LinkWeakPtr parent_link_;

};
}
#endif
52 changes: 46 additions & 6 deletions urdf_sensor/include/urdf_sensor/types.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,20 +32,60 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/

/* Author: Steve Peters */
/* Author: Robert Haschke */

#ifndef URDF_SENSOR_TYPES_H
#define URDF_SENSOR_TYPES_H

#include <memory>
#include "urdf_model/types.h"
#include "urdf_model/pose.h"

namespace urdf {

namespace urdf{
URDF_TYPEDEF_CLASS_POINTER(Sensor);
URDF_TYPEDEF_CLASS_POINTER(SensorBase);
URDF_TYPEDEF_CLASS_POINTER(Camera);
URDF_TYPEDEF_CLASS_POINTER(Ray);

class SensorBase;
class SensorBase
{
public:
virtual void clear() = 0;
virtual ~SensorBase(void) {}
};

// typedef shared pointers
typedef std::shared_ptr<SensorBase> SensorBaseSharedPtr;
/** Sensor class is wrapper comprising generic sensor information
* like name, update rate, sensor frame (parent link + origin transform)
* TODO: think about mergin with SensorBase
*/
class Sensor
{
public:
Sensor() { this->clear(); };

/// sensor name must be unique
std::string name_;

/// update rate in Hz
double update_rate_;

/// name of parent link this sensor is attached to
std::string parent_link_;

/// transform from parent frame sensor frame
Pose origin_;

/// sensor
SensorBaseSharedPtr sensor_;

void clear()
{
name_.clear();
parent_link_.clear();
origin_.clear();
sensor_.reset();
}
};

}

Expand Down

0 comments on commit ec55e6b

Please sign in to comment.