24 from std_srvs.srv
import Trigger, TriggerResponse
25 from trajectory_msgs.msg
import JointTrajectory, JointTrajectoryPoint
26 from control_msgs.msg
import FollowJointTrajectoryAction, FollowJointTrajectoryResult
27 from simple_script_server
import *
32 super(PythonAPITest, self).
__init__(*args)
33 rospy.init_node(
'test_python_api_test')
43 if not rospy.has_param(
'~command'):
44 self.fail(
'Parameter command does not exist on ROS Parameter Server')
45 command = rospy.get_param(
'~command')
47 self.fail(
'Parameters not set properly')
51 component_name =
"arm" 55 as_name =
"/" + component_name +
"_controller/follow_joint_trajectory" 59 self.
move_test(component_name,
"grasp-to-tray")
61 elif command ==
"stop":
63 ss_name =
"/arm_controller/" + command
65 rospy.Service(ss_name, Trigger, self.
ss_cb)
70 self.fail(
'Service Server not called')
71 elif command ==
"init":
73 ss_name =
"/arm_controller/" + command
75 rospy.Service(ss_name, Trigger, self.
ss_cb)
80 self.fail(
'Service Server not called')
81 elif command ==
"recover":
83 ss_name =
"/arm_controller/" + command
85 rospy.Service(ss_name, Trigger, self.
ss_cb)
87 self.sss.recover(
"arm")
90 self.fail(
'Service Server not called')
92 self.fail(
"Command not known to test script")
98 self.sss.move(component_name,parameter_name)
102 self.fail(
'No goal received at action server')
105 param_string = self.
ns_global_prefix +
"/" + component_name +
"/joint_names" 106 if not rospy.has_param(param_string):
107 error_msg =
"parameter " + param_string +
" does not exist on ROS Parameter Server" 109 joint_names = rospy.get_param(param_string)
112 if type(parameter_name)
is str:
113 param_string = self.
ns_global_prefix +
"/" + component_name +
"/" + parameter_name
114 if not rospy.has_param(param_string):
115 error_msg =
"parameter " + param_string +
" does not exist on ROS Parameter Server" 117 param = rospy.get_param(param_string)
119 param = parameter_name
122 if not type(param)
is list:
123 error_msg =
"no valid parameter for " + component_name +
": not a list, aborting..." 130 if type(point)
is str:
131 if not rospy.has_param(self.
ns_global_prefix +
"/" + component_name +
"/" + point):
132 error_msg =
"parameter " + self.
ns_global_prefix +
"/" + component_name +
"/" + point +
" does not exist on ROS Parameter Server, aborting..." 134 point = rospy.get_param(self.
ns_global_prefix +
"/" + component_name +
"/" + point)
137 elif type(point)
is list:
138 rospy.logdebug(
"point is a list")
140 error_msg =
"no valid parameter for " + component_name +
": not a list of lists or strings, aborting..." 145 if not len(point) == len(joint_names):
146 error_msg =
"no valid parameter for " + component_name +
": dimension should be " + len(joint_names) +
" and is " + len(point) +
", aborting..." 151 if not ((type(value)
is float)
or (type(value)
is int)):
153 error_msg =
"no valid parameter for " + component_name +
": not a list of float or int, aborting..." 157 traj_msg = JointTrajectory()
158 traj_msg.header.stamp = rospy.Time.now()+rospy.Duration(0.5)
159 traj_msg.joint_names = joint_names
162 point_msg = JointTrajectoryPoint()
163 point_msg.positions = point
164 point_msg.time_from_start=rospy.Duration(3*point_nr)
165 traj_msg.points.append(point_msg)
171 if not (len(traj_msg.points) == len(self.traj.points)):
172 self.fail(
'Not the same amount of points in trajectory')
177 for i
in range(len(traj_msg.points)):
181 if not (len(traj_msg.points[i].positions) == len(self.traj.points[i].positions)):
182 self.fail(
'Not the same amount of values in point')
185 for j
in range(len(traj_msg.points[i].positions)):
186 if not (traj_msg.points[i].positions[j] == self.traj.points[i].positions[j]):
187 self.fail(
'Not the same values in point')
191 result = FollowJointTrajectoryResult()
195 print(
"action server callback")
196 self.as_server.set_succeeded(result)
200 res = TriggerResponse()
204 if __name__ ==
'__main__':
206 rostest.run(
'rostest',
'test_python_apt_test', PythonAPITest, sys.argv)
207 except KeyboardInterrupt
as e:
def move_test(self, component_name, parameter_name)
def test_python_api(self)
as_server
as_name = "/" + component_name + "_controller/joint_trajectory_action" self.as_server = actionlib...
Simple script server class.