Skip to content

Commit

Permalink
Fix deprecation warning in paramater declaration (#1280)
Browse files Browse the repository at this point in the history
  • Loading branch information
kumar-sanjeeev authored Sep 11, 2024
1 parent c08bdab commit 48a7f8b
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ def __init__(self):
# Read all positions from parameters
self.goals = []
for name in goal_names:
self.declare_parameter(name)
self.declare_parameter(name, rclpy.Parameter.Type.DOUBLE_ARRAY)
goal = self.get_parameter(name).value
if goal is None or len(goal) == 0:
raise Exception(f'Values for goal "{name}" not set!')
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@
import rclpy
from rclpy.node import Node
from builtin_interfaces.msg import Duration
from rcl_interfaces.msg import ParameterDescriptor

from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint
from sensor_msgs.msg import JointState
Expand Down Expand Up @@ -67,8 +66,7 @@ def __init__(self):
# Read all positions from parameters
self.goals = [] # List of JointTrajectoryPoint
for name in goal_names:
self.declare_parameter(name, descriptor=ParameterDescriptor(dynamic_typing=True))

self.declare_parameter(name, rclpy.Parameter.Type.DOUBLE_ARRAY)
point = JointTrajectoryPoint()

def get_sub_param(sub_param):
Expand Down

0 comments on commit 48a7f8b

Please sign in to comment.