~robot3d-team/robot3d/trunk

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
//! Robot Actor base class.

/*!
 *
 * Handles general functions of the robot class.
 *
 * @author Lutz Winkler
 *
 */

#ifndef ROBOTACTORBASE_H_
#define ROBOTACTORBASE_H_

// ODE
#include <ode/ode.h>

// Open scene graph
#include <osg/Texture2D>
#include <osg/Geode>
#include <osg/Geometry>

// Delta3D files
#include <dtGame/gameactor.h>
#include <dtCore/refptr.h>
#include <dtCore/object.h>
#include <dtCore/camera.h>
#include <dtCore/transform.h>
#include <dtDAL/namedparameter.h>
#include <dtUtil/coordinates.h>
#include <dtGame/actorupdatemessage.h>
#include <dtGame/basemessages.h>

// Robot3D files
#include <srCore/export.h>
#include <srCore/xmlConfig.h>
#include <srCore/robot/objectBase.h>
#include <srCore/actuator/actuatorBase.h>
#include <srCore/sensor/sensorBase.h>
#include <srCore/actuator/connectorBase.h>
#include <srCore/robot/robotActorBase.h>


namespace srCore {

class ConnectorBase;
class ActuatorBase;
class SensorBase;
class ObjectBase;


class ROBOT_EXPORT RobotActorBase : public dtGame::GameActor
{
public:

	//! Constructs the robot actor.
	RobotActorBase(dtGame::GameActorProxy &proxy);


	/**
	 * This ID will be used for collision handling in the ode. It is not
	 * a UUID.
	 */
	virtual void 		setID(long int id);
	virtual void 		setSelectionState(bool selState);
	virtual void 		setConnectorStates(int state);

	/**
	 * Returns the robot ID. This ID will be used for collision handling in the ode. It is not
	 * a UUID.
	 */
	virtual long int 	getID() const { return myID; };
	virtual bool 		getSelectionState() { return selectionState; };
	virtual int 		getConnectorStates() const {

		int state = 0;
		int bitCheck = 1;
		for (unsigned int i=0; i<myConnectors.size(); i++) {

			if (myConnectors[i]->getState() != ConnectorBase::DISCONNECTED) state += bitCheck;
			bitCheck = bitCheck << 1;

		}

		return state;

	};


	//! Returns the osgGroup. Will be used for shadows or later special scenes used for sensors
	virtual dtCore::RefPtr<osg::Group> getOsgGroup() const { return osgGroup; };

	//! Dirty short-cut to enable/disable physics
	void EnableDynamics(bool enable);

	//! Sets global position of the robot
	virtual void setTranslation(const osg::Vec3& pos);

	//! Sets global orientation (hpr) of the robot
	virtual void setRotation(const osg::Vec3& rot);

	/**
	 * Gets global position of the robot. It is not position, it is translation.
	 * @deprecated
	 */
	virtual osg::Vec3f getTranslation() const { return myPos; };

	virtual osg::Vec3f getPosition() const { return myPos; };

	virtual void setPosition(const osg::Vec3 &pos);

	//! Gets global orientation of the robot (hpr)
	virtual osg::Vec3f getRotation(); 			// const { return myRot; };

	dtCore::UniqueId* getBusID() const { return globalCommID; };
	void setBusID(dtCore::UniqueId* id) {globalCommID = id;};

	/**
	 * This method is an invokable called when an object is local and
	 * receives a tick.
	 * @param tickMessage A message containing tick related information.
	 */
	virtual void TickLocal(const dtGame::Message &tickMessage);

	/**
	 * This method is an invokable called when an object is remote and
	 * receives a tick.
	 * @param tickMessage A message containing tick related information.
	 */
	virtual void TickRemote(const dtGame::Message &tickMessage);

	/**
	 * Generic handler for messages. Overridden from base class.
	 * This is the default invokable on GameActorProxy.
	 */
	virtual void ProcessMessage(const dtGame::Message &message);


	/** Called when the actor has been added to the game manager.
	 * You can respond to OnEnteredWorld on either the proxy or actor or both.
	 */
	virtual void OnEnteredWorld();

	inline std::vector<RobotActorBase* > getConnectedRobots() {
		std::vector<RobotActorBase* > connectedRobots;
		getConnectedRobots(connectedRobots);
		return connectedRobots;
	};

	inline std::vector<BodyBase* > getConnectedBodies(BodyBase* parentBody) {

		std::vector<BodyBase* > connectedBodies;

		getConnectedBodies(connectedBodies, parentBody);
		return connectedBodies;
	};

	inline std::vector<dtCore::RefPtr<SensorBase> > getSensors() const {return mySensors; }

	//! Returns a list of actuators that are attached to the robot
	inline std::vector<dtCore::RefPtr<ActuatorBase> > getActuators() const {return myActuators;}

	//! Returns a list of bodies the robot consists of
	inline std::vector<dtCore::RefPtr<BodyBase> > getBodies() const {return myBodies;}

	//! Returns a list of connectors that are attached to the robot
	inline std::vector<dtCore::RefPtr<ConnectorBase> > getConnectors() const {return myConnectors;}

	//! Returns a list of objects that are attached to the robot and not of the types above
	inline std::vector<dtCore::RefPtr<ObjectBase> > getObjects() const {return myObjects;}

	//! If true, the collision geometry of the robot will be rendered
	inline void renderCollisionGeometry(bool renderIt) {

		for (unsigned int i=0; i<myBodies.size(); i++)
			myBodies[i]->RenderCollisionGeometry(false);
//			myBodies[i]->renderCollisionGeometry(renderIt);

	}

	//! colors the robot -- todo: stays in conflict with RenderCollisionGeometry
	inline void colorCollisionGeometry(osg::Vec4 color) {

//		for (unsigned int i=0; i<myBodies.size(); i++)
//			myBodies[i]->colorBody(color);

	}

	//! sends message to the bus, robots within the same organsim receive that message
	void sendBusMessage(const std::string& message);

	inline std::string getLastBusMessage(const std::string& message) const {return globalMsg;};

	inline void setSensorData(std::vector<SensorInitData> newSensorData) { sensorData = newSensorData; };

	inline void setInitialJointAngles(std::vector<float> initialJointAngles) { jointAngles = initialJointAngles;};
protected:

	virtual void initialize();

	void getConnectedBodies (std::vector<BodyBase* > &connectedBodies, BodyBase* bodyNode);
	void getConnectedRobots (std::vector<RobotActorBase* > &connectedRobots);
	osg::Vec3f myPos, myRot;						// position and rotation vectors of the first body element
	// register this robot and all other robots connected to this robot to the same message type
	void registerToCommBus(dtCore::UniqueId* id);
	void unregisterFromCommBus();

	void addBody(BodyBase* body);
	void addActuator(ActuatorBase* actuator);
	void addConnector(ConnectorBase* connector);
	void addSensor(SensorBase* sensor);

	dtCore::UniqueId* globalCommID;
	std::string globalMsg;

	bool selectionState;							//is true if this robot is currently selected
	long int myID;
	int connectorStates;
	dtCore::RefPtr<osg::Group> osgGroup;							// all drawables that should be detected by sensors


	std::vector<dtCore::RefPtr<SensorBase> > mySensors;
	std::vector<dtCore::RefPtr<ActuatorBase> > myActuators;
	std::vector<dtCore::RefPtr<BodyBase> > myBodies;
	std::vector<dtCore::RefPtr<ConnectorBase> > myConnectors;		// might be useful/necessary to have an extra container for the connectors
	std::vector<dtCore::RefPtr<ObjectBase> > myObjects;

	std::vector<SensorInitData> sensorData;

	//! inital joint angles
	std::vector<float> jointAngles;

public:
	 ~RobotActorBase();

private:
	osg::Vec3f initPos, initRot;						// init position and rotation how the robot has been created
};


/**
 * Our proxy class for the robot actor.  The proxy contains properties,
 * invokables, and robot actor.
 */
class ROBOT_EXPORT RobotActorBaseProxy : public dtGame::GameActorProxy
{
public:

	//! Constructs the proxy.
	RobotActorBaseProxy();

	//! Set Robots ID
	virtual void setID(long int id);

	//! Get Robots ID
	virtual long int getID();

	virtual void setConnectorStates(int state);
	virtual int getConnectorStates();


	//! Translate Robot -- use only if physics are deactived or robot is not attached to another one
	virtual void setTranslation(osg::Vec3 pos);

	//! Get global translation of the robot
	virtual osg::Vec3 getTranslation();

	//! Rotate Robot -- use only if physics are deactived or robot is not attached to another one
	virtual void setRotation(osg::Vec3 rot);

	//! Get global rotation of the robot
	virtual osg::Vec3 getRotation();

	//! Creates the properties that are custom to the robot proxy.
	virtual void BuildPropertyMap();

	//! Add a sensor to robot.
	virtual void setSensors(std::vector<SensorInitData> sensors);

	//! Set inital joint angles
	virtual void setInitialJointAngles(std::vector<float> jointAngles);

protected:
	virtual ~RobotActorBaseProxy();

	//! Creates an instance of our robot tank actor
	virtual void CreateActor();

	/**
	 *  Called when this proxy is added to the game manager (ie, the "world")
	 * You can respond to OnEnteredWorld on either the proxy or actor or both.
	 */
	virtual void OnEnteredWorld();
	
private:
	
	osg::Vec3 rot;
	
};
}


#endif /*ROBOTACTORBASE_H_*/