Skip to content
This repository was archived by the owner on Feb 21, 2021. It is now read-only.

JderobotComm C++ for kobuki#683

Merged
fqez merged 32 commits into
JdeRobot:masterfrom
aitormf:libs/jderobotcommcpp/666
Feb 23, 2017
Merged

JderobotComm C++ for kobuki#683
fqez merged 32 commits into
JdeRobot:masterfrom
aitormf:libs/jderobotcommcpp/666

Conversation

@aitormf
Copy link
Copy Markdown
Collaborator

@aitormf aitormf commented Feb 6, 2017

Using JdeRobotComm, our tools can use ROS messages or Ice interfaces for laser, motors, cameras and pose3d.

kobukiViewer also has been adapted to use jderobotComm . Example of laser part of config file:

# 0 -> Deactivate, 1 -> Ice , 2 -> ROS
kobukiViewer.Laser=1
kobukiViewer.Laser.Proxy=Laser:tcp -h localhost -p 9001		  
kobukiViewer.Laser.Topic=/scan
kobukiViewer.Laser.Name=kobukiViewerLaser

To add JdeRobotComm laser interface to a tool, you only need put:

this->laserClient = JdeRobotComm::getLaserClient(ic, "kobukiViewer.Laser");

then, using laserClient->getLaserData(), you will receive a JdeRobotTypes::LaserData that contains:

class LaserData {
	public:
	    std::vector values;
	    float minAngle = 0; //Angle of first value (rads)
	    float maxAngle = 0; // Angle of last value (rads)
	    float minRange = 0; // Max Range posible (meters)
	    float maxRange = 0; //Min Range posible (meters)
	    double timeStamp = 0; //seconds
	};

for the others interfaces is the same:

class CMDVel {
	public:
		float vx = 0; /**< % vel in x[m/s] (use this for V in wheeled robots)*/
	    float vy = 0; /**< %vel in y[m/s] */
	    float vz = 0; /**< %vel in z[m/s] */
	    float ax = 0; /**< %angular vel in X axis [rad/s] */
	    float ay = 0; /**< %angular vel in Y axis [rad/s] */
	    float az = 0; /**< %angular vel in Z axis [rad/s] (use this for W in wheeled robots)*/
	    double timeStamp = 0; /**< %Time stamp [s] */
	};

class Image {
	public:

	    int height = 0; /**< %Image height [pixels] */
	    int width = 0; /**< %Image width [pixels] */
	    double timeStamp = 0; /**< %Time stamp [s] */
	    std::string format = ""; /**< %Image format string (RGB8, BGR,...) */
	    cv::Mat data = cv::Mat::zeros(3,3, CV_8UC3); /**< The image data itself */
	};

	class Pose3d {
	public:
		float x = 0; /**< %X coord [meters] */
	    float y = 0; /**< %Y coord [meters] */
	    float z = 0; /**< %Z coord [meters] */
	    float h = 0; /**< %H param */
	    float yaw = 0; /**< %Yaw angle[rads] */
	    float pitch = 0; /**< %Pitch angle[rads] */
	    float roll = 0; /**< %Roll angle[rads] */
	    std::vector q = {0,0,0,0}; /**< %Quaternion */
	    double timeStamp = 0; /**< %Time stamp [s] */
	};

all new internal types are in "src/types".

jderobotcomm_cpp is in "src/libs" and internally is divided in three blocks:

  • interfaces: provides the interfaces to be used by clients
  • ros: ros listeners and publishers
  • ice: ice interfaces

Also I have added two Cmake modules to can use python3 and python2 in the same project because we use python 3 but ROS uses python2.
With a macro added to root CMakeLists we can switch between versions using: usePython(MajorVersionNumber), for example:

 
usePython(3)

This PR solves #548, #551, #552, #640, #644, #655, #662, #665, #666

…ns of tools. It will replace to parallelIce
…nd solved bugs in camera and laser listener
…n2 in the same project

Also added in root Cmake a macro to can switch between versions using: usePython(MajorVersionNumber), for example: usePython(3)
Sign up for free to subscribe to this conversation on GitHub. Already have an account? Sign in.

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

2 participants