| @@ -10,6 +10,7 @@ class JTCPublisher(Node): | |||||
| self.group_tags_ = [ "e1", "e2", "e3", "e4", "e5", "e6"] | self.group_tags_ = [ "e1", "e2", "e3", "e4", "e5", "e6"] | ||||
| self.publisher_ = {} | self.publisher_ = {} | ||||
| trajectory = {} | |||||
| for tag in self.group_tags_: | for tag in self.group_tags_: | ||||
| @@ -22,7 +23,7 @@ class JTCPublisher(Node): | |||||
| direction = -1 | direction = -1 | ||||
| self.publisher_[tag] = self.create_publisher(JointTrajectory, controller_topic , 10) | self.publisher_[tag] = self.create_publisher(JointTrajectory, controller_topic , 10) | ||||
| trajectory = JointTrajectory( | |||||
| trajectory[tag] = JointTrajectory( | |||||
| joint_names = [ f"c{group_num}_joint", f"f{group_num}_joint", f"t{group_num}_joint" ], | joint_names = [ f"c{group_num}_joint", f"f{group_num}_joint", f"t{group_num}_joint" ], | ||||
| points = [ | points = [ | ||||
| JointTrajectoryPoint (time_from_start = Duration(sec = 1), positions = [direction * 0, direction * -1.4, direction * 0]), | JointTrajectoryPoint (time_from_start = Duration(sec = 1), positions = [direction * 0, direction * -1.4, direction * 0]), | ||||
| @@ -37,7 +38,7 @@ class JTCPublisher(Node): | |||||
| JointTrajectoryPoint (time_from_start = Duration(sec = 10), positions =[direction * 0, direction * -1.4, direction * 0]), | JointTrajectoryPoint (time_from_start = Duration(sec = 10), positions =[direction * 0, direction * -1.4, direction * 0]), | ||||
| ] | ] | ||||
| ) | ) | ||||
| self.publisher_[tag].publish(trajectory) | |||||
| self.publisher_[tag].publish(trajectory[tag]) | |||||
| def main(args = None): | def main(args = None): | ||||
| rclpy.init(args=args) | rclpy.init(args=args) | ||||