panda_control_server

This node sets up a number of services that can be used to control the Panda Emika Franka robot.

Source code

 1
 2from panda_gazebo.core.control_server import PandaControlServer
 3
 4if __name__ == "__main__":  # noqa: C901
 5    rospy.init_node("panda_control_server")
 6
 7    # Get ROS parameters.
 8    try:  # Auto fill joint traj position field if left empty.
 9        autofill_traj_positions = rospy.get_param("~autofill_traj_positions")
10    except KeyError:
11        autofill_traj_positions = False
12    try:
13        load_gripper = rospy.get_param("~load_gripper")
14    except KeyError:
15        load_gripper = True
16    try:  # Check if set joint commands service should be loaded.
17        load_set_joint_commands_service = rospy.get_param(
18            "~load_set_joint_commands_service"
19        )
20    except KeyError:
21        load_set_joint_commands_service = True
22    try:  # Check if arm follow joint trajectory action should be loaded.
23        load_arm_follow_joint_trajectory_action = rospy.get_param(
24            "~load_arm_follow_joint_trajectory_action"
25        )
26    except KeyError:
27        load_arm_follow_joint_trajectory_action = False
28    try:  # Check if extra services should be loaded.
29        load_extra_services = rospy.get_param("~load_extra_services")
30    except KeyError:
31        load_extra_services = False
32    try:  # The rate with which we check for the used controllers to be active.
33        controllers_check_rate = rospy.get_param("~controllers_check_rate")
34    except KeyError:
35        controllers_check_rate = 0.1
36
37    # Start control server.
38    control_server = PandaControlServer(
39        autofill_traj_positions=autofill_traj_positions,
40        load_gripper=load_gripper,
41        load_set_joint_commands_service=load_set_joint_commands_service,
42        load_arm_follow_joint_trajectory_action=load_arm_follow_joint_trajectory_action,
43        load_extra_services=load_extra_services,
44        controllers_check_rate=controllers_check_rate,
45    )
46    rospy.spin()  # Maintain the service open.

Module Contents

panda_control_server.autofill_traj_positions[source]