Skip to content

Commit

Permalink
[naoqi_pose] get current state of AutonomousLife (#87)
Browse files Browse the repository at this point in the history
* [naoqi_pose] get current state of AutonomousLife
  • Loading branch information
kochigami authored and nlyubova committed Feb 2, 2018
1 parent b4113d6 commit 04aa56c
Showing 1 changed file with 30 additions and 1 deletion.
31 changes: 30 additions & 1 deletion naoqi_pose/nodes/pose_controller.py
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,8 @@

from naoqi_driver.naoqi_node import NaoqiNode

from std_srvs.srv import Empty, EmptyResponse
from std_msgs.msg import String
from std_srvs.srv import Empty, EmptyResponse, Trigger, TriggerResponse
from sensor_msgs.msg import JointState

class PoseController(NaoqiNode):
Expand Down Expand Up @@ -78,6 +79,8 @@ def __init__(self):
if initStiffness > 0.0 and initStiffness <= 1.0:
self.motionProxy.stiffnessInterpolation('Body', initStiffness, 0.5)

# advertise topics:
self.getLifeStatePub = rospy.Publisher("get_life_state", String, queue_size=10)

# start services / actions:
self.enableStiffnessSrv = rospy.Service("body_stiffness/enable", Empty, self.handleStiffnessSrv)
Expand All @@ -86,6 +89,7 @@ def __init__(self):
self.restSrv = rospy.Service("rest", Empty, self.handleRestSrv)
self.enableLifeSrv = rospy.Service("life/enable", Empty, self.handleLifeSrv)
self.disableLifeSrv = rospy.Service("life/disable", Empty, self.handleLifeOffSrv)
self.getLifeSrv = rospy.Service("life/get_state", Trigger, self.handleGetLifeSrv)


#Start simple action servers
Expand Down Expand Up @@ -208,6 +212,17 @@ def handleLifeOffSrv(self, req):
rospy.logerr("Exception while disabling life state:\n%s", e)
return None

def handleGetLifeSrv(self, req):
try:
res = TriggerResponse()
res.success = True
res.message = self.lifeProxy.getState()
rospy.loginfo("current life state is " + str(res.message))
return res
except RuntimeError, e:
rospy.logerr("Exception while getting life state:\n%s", e)
return None

def jointTrajectoryGoalMsgToAL(self, goal):
"""Helper, convert action goal msg to Aldebraran-style arrays for NaoQI"""
names = list(goal.trajectory.joint_names)
Expand Down Expand Up @@ -407,9 +422,23 @@ def executeBodyPoseWithSpeed(self, goal):
#~ Return success
self.bodyPoseWithSpeedServer.set_succeeded()

def run(self):
while self.is_looping():
try:
if self.getLifeStatePub.get_num_connections() > 0:
get_life_state_msg = String()
get_life_state_msg.data = self.lifeProxy.getState()
self.getLifeStatePub.publish(get_life_state_msg)

except RuntimeError, e:
print "Error accessing ALMotion, ALRobotPosture, ALAutonomousLife, exiting...\n"
print e
rospy.signal_shutdown("No NaoQI available anymore")

if __name__ == '__main__':

controller = PoseController()
controller.start()
rospy.loginfo("nao pose_controller running...")
rospy.spin()

Expand Down

1 comment on commit 04aa56c

@warp1337
Copy link

@warp1337 warp1337 commented on 04aa56c Feb 7, 2018

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You dont want to run the thread as fast as possible. I would introduce a sleep, as of now, this script consumes 100% CPU.

Please sign in to comment.