34 import roslib; roslib.load_manifest(
'calibration_launch')
39 import joint_states_settler.msg
40 import monocam_settler.msg
41 import image_cb_detector.msg
42 import laser_cb_detector.msg
43 import interval_intersection.msg
45 from trajectory_msgs.msg
import JointTrajectory
46 from trajectory_msgs.msg
import JointTrajectoryPoint
50 def __init__(self, cam_config, chain_config, laser_config, controller_config):
53 rospy.logdebug(
"Constructing Cameras:")
55 for name
in cam_config.keys():
56 rospy.logdebug(
" Constructing CamID [%s]" % name)
60 rospy.logdebug(
"Constructing Chains:")
62 for name
in chain_config.keys():
63 rospy.logdebug(
" Constructing ChainID [%s]" % name)
67 rospy.logdebug(
"Constructing Lasers:")
69 for laser_id
in laser_config.keys():
70 rospy.logdebug(
" Constructing LaserID [%s]" % laser_id)
74 rospy.logdebug(
"Constructing Controllers:")
76 for controller_id
in controller_config.keys():
77 rospy.logdebug(
" Constructing ControllerID [%s]" % controller_id)
86 intersect_goal = interval_intersection.msg.ConfigGoal();
88 intersect_goal.topics = [x[
'cam_id']
for x
in config[
"camera_measurements"]] + [x[
'chain_id']
for x
in config[
"joint_measurements"]] + [x[
'laser_id']
for x
in config[
"laser_measurements"]]
90 intersect_goal.topics = [x[
'cam_id']
for x
in config[
"camera_measurements"]] + [x[
'chain_id']
for x
in config[
"joint_measurements"]]
91 self._intersect_ac.send_goal(intersect_goal)
94 rospy.logdebug(
"Reconfiguring The Cameras")
95 for cur_cam
in config[
"camera_measurements"]:
99 rospy.logdebug(
"Reconfiguring The Chains")
100 for cur_chain
in config[
"joint_measurements"]:
104 rospy.logdebug(
"Reconfiguring The Lasers")
106 for cur_laser
in config[
"laser_measurements"]:
112 rospy.logdebug(
"Sending Controller Commands")
113 for cur_controller
in config[
"joint_commands"]:
120 class ChainConfigManager:
125 raise Exception(
"Invalid chain description")
138 if self.
_state == next_config_name:
139 rospy.logdebug(
" %s: Configured correctly as [%s]" % (self_.chain_id, self.
_state))
141 rospy.logdebug(
" %s: Need to transition [%s] -> [%s]" % (self.
_chain_id, self.
_state, next_config_name))
143 next_config = self.
_configs[
"configs"][next_config_name]
144 settler_config = next_config[
"settler"]
146 goal = joint_states_settler.msg.ConfigGoal()
147 goal.joint_names = settler_config[
"joint_names"]
148 goal.tolerances = settler_config[
"tolerances"]
149 goal.max_step = rospy.Duration(settler_config[
"max_step"])
150 goal.cache_size = settler_config[
"cache_size"]
153 self._settler_ac.send_goal(goal)
164 raise Exception(
"Invalid camera description")
178 if self.
_state == next_config_name:
179 rospy.logdebug(
" %s: Configured correctly as [%s]" % (self_.cam_id, self.
_state))
181 rospy.logdebug(
" %s: Need to transition [%s] -> [%s]" % (self.
_cam_id, self.
_state, next_config_name))
183 next_config = self.
_configs[
"configs"][next_config_name]
186 settler_config = next_config[
"settler"]
187 goal = monocam_settler.msg.ConfigGoal()
188 goal.tolerance = settler_config[
"tolerance"]
189 goal.ignore_failures = settler_config[
"ignore_failures"]
190 goal.max_step = rospy.Duration(settler_config[
"max_step"])
191 goal.cache_size = settler_config[
"cache_size"]
192 self._settler_ac.send_goal(goal)
195 cb_detector_config = next_config[
"cb_detector"]
196 if not cb_detector_config[
"active"]:
197 rospy.logerr(
"Can't deal with inactive cb_detector")
198 goal = image_cb_detector.msg.ConfigGoal()
199 goal.num_x = cb_detector_config[
"num_x"]
200 goal.num_y = cb_detector_config[
"num_y"]
203 goal.width_scaling = cb_detector_config[
"width_scaling"]
204 goal.height_scaling = cb_detector_config[
"height_scaling"]
205 goal.subpixel_window = cb_detector_config[
"subpixel_window"]
206 goal.subpixel_zero_zone = cb_detector_config[
"subpixel_zero_zone"]
207 self._led_detector_ac.send_goal(goal)
210 led_detector_config = next_config[
"led_detector"]
211 if led_detector_config[
"active"]:
212 rospy.logerr(
"Can't deal with an active led_detector")
222 raise Exception(
"Invalid laser description")
236 if self.
_state == next_config_name:
237 rospy.logdebug(
" %s: Configured correctly as [%s]" % (self_.laser_id, self.
_state))
239 rospy.logdebug(
" %s: Need to transition [%s] -> [%s]" % (self.
_laser_id, self.
_state, next_config_name))
241 next_config = self.
_configs[
"configs"][next_config_name]
244 settler_config = next_config[
"settler"]
245 goal = monocam_settler.msg.ConfigGoal()
246 goal.tolerance = settler_config[
"tolerance"]
247 goal.ignore_failures = settler_config[
"ignore_failures"]
248 goal.max_step = rospy.Duration(settler_config[
"max_step"])
249 goal.cache_size = settler_config[
"cache_size"]
250 self._settler_ac.send_goal(goal)
253 cb_detector_config = next_config[
"cb_detector"]
254 if not cb_detector_config[
"active"]:
255 rospy.logerr(
"Not sure yet how to deal with inactive cb_detector")
256 goal = laser_cb_detector.msg.ConfigGoal()
257 goal.num_x = cb_detector_config[
"num_x"]
258 goal.num_y = cb_detector_config[
"num_y"]
259 goal.spacing_x = cb_detector_config[
"spacing_x"]
260 goal.spacing_y = cb_detector_config[
"spacing_y"]
261 goal.width_scaling = cb_detector_config[
"width_scaling"]
262 goal.height_scaling = cb_detector_config[
"height_scaling"]
263 goal.subpixel_window = cb_detector_config[
"subpixel_window"]
264 goal.subpixel_zero_zone = cb_detector_config[
"subpixel_zero_zone"]
265 goal.flip_horizontal = cb_detector_config[
"flip_horizontal"]
266 goal.min_intensity = cb_detector_config[
"min_intensity"]
267 goal.max_intensity = cb_detector_config[
"max_intensity"]
268 self._cb_detector_ac.send_goal(goal)
280 raise Exception(
"Invalid chain description")
283 self.
_pub = rospy.Publisher(self.
_config[
"topic"], JointTrajectory)
292 rospy.logdebug(
" Sending cmd to controller [%s]"%self.
_controller_id)
293 cmd_msg = JointTrajectory()
294 cmd_msg.header.stamp = rospy.Time().now()
295 cmd_msg.joint_names = self.
_config[
"joint_names"]
296 cmd_msg.points = [self.
_build_segment(x)
for x
in cmd[
"segments"]]
297 self._pub.publish(cmd_msg)
300 segment = JointTrajectoryPoint()
301 segment.positions = config[
"positions"]
302 segment.velocities = [0] * len(config[
"positions"])
303 segment.time_from_start = rospy.Duration(config[
"duration"])
def __init__(self, controller_id, config)
def _build_segment(self, config)
def reconfigure(self, next_config_name)
def reconfigure(self, config)
def __init__(self, cam_id, configs)
def send_command(self, cmd)
def __init__(self, chain_id, configs)
def __init__(self, laser_id, configs)
def __init__(self, cam_config, chain_config, laser_config, controller_config)
def reconfigure(self, next_config_name)
def reconfigure(self, next_config_name)