Revision c5a47e56
client/cpp/CMakeLists.txt | ||
---|---|---|
24 | 24 |
SET(DATADIR "${PREFIX}/share/hlrc_client") |
25 | 25 |
|
26 | 26 |
####################################### |
27 |
# check if we have RSB support: |
|
28 |
option(WITH_RSB "WITH_RSB" ON) |
|
27 |
####################################### |
|
28 |
#allow forced disable of RSB |
|
29 |
option(IGNORE_RSB "IGNORE_RSB" OFF) |
|
29 | 30 |
|
30 |
IF(WITH_RSB) |
|
31 |
####################################### |
|
32 |
# check if we have RSB support: |
|
33 |
IF (IGNORE_RSB) |
|
34 |
MESSAGE(INFO "RSB disabled per command line flag IGNORE_RSB") |
|
35 |
ELSE (IGNORE_RSB) |
|
31 | 36 |
FIND_PACKAGE(RSB 0.11) |
32 | 37 |
IF (RSB_FOUND) |
33 | 38 |
#RSB |
... | ... | |
56 | 61 |
message(STATUS "RSB Support is ON") |
57 | 62 |
add_definitions(-DRSB_SUPPORT=1) |
58 | 63 |
ENDIF (RSB_FOUND) |
59 |
ENDIF(WITH_RSB) |
|
64 |
ENDIF(IGNORE_RSB) |
|
65 |
|
|
60 | 66 |
################################################################ |
61 | 67 |
# check for ROS support: |
62 | 68 |
find_package(catkin) |
client/cpp/examples/random_gaze/main.cpp | ||
---|---|---|
58 | 58 |
gaze.vergence = 0.0; |
59 | 59 |
|
60 | 60 |
//absolute mode |
61 |
gaze.type = RobotGaze::ABSOLUTE; |
|
61 |
gaze.gaze_type = RobotGaze::ABSOLUTE;
|
|
62 | 62 |
gaze.timestamp = RobotGaze::now(); |
63 | 63 |
|
64 | 64 |
//robot_controller->set_current_emotion(RobotEmotion(RobotEmotion::ANGRY)); |
client/cpp/include/RobotGaze.h | ||
---|---|---|
38 | 38 |
vergence = 0.0; |
39 | 39 |
pan_offset = 0.0; |
40 | 40 |
tilt_offset = 0.0; |
41 |
type = ABSOLUTE; |
|
41 |
gaze_type = ABSOLUTE;
|
|
42 | 42 |
} |
43 | 43 |
|
44 | 44 |
static double now(){ |
... | ... | |
55 | 55 |
|
56 | 56 |
double timestamp; |
57 | 57 |
|
58 |
int type; |
|
58 |
int gaze_type;
|
|
59 | 59 |
|
60 | 60 |
float pan, tilt, roll, vergence; |
61 | 61 |
float pan_offset, tilt_offset; |
client/cpp/src/MiddlewareROS.cpp | ||
---|---|---|
154 | 154 |
goal.pan_offset = target.pan_offset; |
155 | 155 |
|
156 | 156 |
//timestamp: |
157 |
//ts = t.sec + t.nsec/1000000000.0; |
|
158 |
uint32_t sec = (uint32_t) target.timestamp; |
|
159 |
uint32_t nsec = (uint32_t)((target.timestamp - sec)*1000000000); |
|
160 |
goal.timestamp = ros::Time(sec, nsec); |
|
157 |
goal.timestamp = ros::Time(target.timestamp); |
|
161 | 158 |
|
162 |
if (target.type == RobotGaze::ABSOLUTE){ |
|
159 |
if (target.gaze_type == RobotGaze::ABSOLUTE){
|
|
163 | 160 |
goal.gaze_type = hlrc_server::gazetargetGoal::GAZETARGET_ABSOLUTE; |
164 | 161 |
}else{ |
165 | 162 |
goal.gaze_type = hlrc_server::gazetargetGoal::GAZETARGET_RELATIVE; |
client/python/hlrc_client/MiddlewareROS.py | ||
---|---|---|
170 | 170 |
goal.vergence = gaze.vergence |
171 | 171 |
goal.pan_offset = gaze.pan_offset |
172 | 172 |
goal.tilt_offset = gaze.tilt_offset |
173 |
|
|
173 |
|
|
174 |
#type |
|
175 |
if (gaze.gaze_type == RobotGaze.ABSOLUTE): |
|
176 |
goal.gaze_type = gazetargetGoal.ABSOLUTE |
|
177 |
else: |
|
178 |
goal.gaze_type = gazetargetGoal.RELATIVE |
|
179 |
|
|
180 |
goal.timestamp = rospy.Time.from_sec(timestamp) |
|
181 |
|
|
182 |
|
|
174 | 183 |
#send the goal to the server |
175 | 184 |
self.gazetarget_client.send_goal(goal) |
176 | 185 |
|
... | ... | |
280 | 289 |
return emotionstateGoal.FEAR |
281 | 290 |
else: |
282 | 291 |
self.logger.error("invalid emotion type %d\n" % (value)) |
283 |
return emotionstateGoal.NEUTRAL |
|
292 |
return emotionstateGoal.NEUTRAL |
client/python/hlrc_client/RobotGaze.py | ||
---|---|---|
26 | 26 |
""" |
27 | 27 |
|
28 | 28 |
class RobotGaze: |
29 |
GAZETARGET_ABSOLUTE = 0 |
|
30 |
GAZETARGET_RELATIVE = 1 |
|
31 |
|
|
29 | 32 |
def __init__(self): |
30 | 33 |
self.pan = 0.0 |
31 | 34 |
self.tilt = 0.0 |
... | ... | |
33 | 36 |
self.vergence = 0.0 |
34 | 37 |
self.pan_offset = 0.0 |
35 | 38 |
self.tilt_offset = 0.0 |
39 |
self.gaze_type = GAZETARGET_ABSOLUTE |
|
40 |
self.timestamp = self.now() |
|
36 | 41 |
|
37 | 42 |
def __str__(self): |
38 |
return "RobotGaze = { PTR={%6.2f %6.2f %6.2f} vergence=%6.2f PT_offset={%6.2f %6.2f} }" \ |
|
39 |
% (self.pan, self.tilt,self.roll,self.vergence,self.pan_offset,self.tilt_offset) |
|
43 |
if (self.gaze_type == GAZETARGET_ABSOLUTE): |
|
44 |
type_s = "ABSOLUTE" |
|
45 |
else: |
|
46 |
type_s = "RELATIVE" |
|
47 |
return "RobotGaze = { PTR={%6.2f %6.2f %6.2f} vergence=%6.2f PT_offset={%6.2f %6.2f} [%s]}" \ |
|
48 |
% (self.pan, self.tilt,self.roll,self.vergence,self.pan_offset,self.tilt_offset,type_s) |
Also available in: Unified diff