Skip to content

Commit

Permalink
change hardware interface port and namespace
Browse files Browse the repository at this point in the history
  • Loading branch information
Michalis Logothetis committed May 14, 2018
1 parent 41447f2 commit 4c8bc35
Show file tree
Hide file tree
Showing 4 changed files with 160 additions and 470 deletions.
47 changes: 47 additions & 0 deletions pa10_hardware_interface/config/real_controllers_ns.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
joint_names: [S1,S2,E1,E2,W1,W2,W3,finger_joint_1,finger_joint_2]

pa10:
# Publish all joint states -----------------------------------
joint_state_controller:
type: joint_state_controller/JointStateController
publish_rate: 50

# Position Controllers ---------------------------------------
arm_controller:
#type: position_controllers/JointGroupPositionController
type: "velocity_controllers/JointTrajectoryController"
#type: "position_controllers/JointTrajectoryController"
#type: "effort_controllers/JointTrajectoryController"

joints:
- S1
- S2
- E1
- E2
- W1
- W2
- W3
gains:
S1: {p: 10.0, i: 0.2, d: 0.05, i_clamp: 2.5}
S2: {p: 10.0, i: 0.2, d: 0.05, i_clamp: 2.5}
E1: {p: 10.0, i: 0.2, d: 0.05, i_clamp: 2.5}
E2: {p: 10.0, i: 0.2, d: 0.05, i_clamp: 2.5}
W1: {p: 10.0, i: 0.2, d: 0.05, i_clamp: 2.5}
W2: {p: 10.0, i: 0.2, d: 0.05, i_clamp: 2.5}
W3: {p: 10.0, i: 0.2, d: 0.05, i_clamp: 2.5}

constraints:
goal_time: 0.5 # Override default
state_publish_rate: 50 # Override default
action_monitor_rate: 20 # Override default
stop_trajectory_duration: 0 # Override default

gripper_controller:
#type: "position_controllers/JointTrajectoryController"
type: "velocity_controllers/JointTrajectoryController"
joints:
- finger_joint_1
- finger_joint_2
gains:
finger_joint_1: &gripper_finger_gains {p: 1.0, d: 0.05, i: 0.1, i_clamp: 1.0}
finger_joint_2: *gripper_finger_gains
49 changes: 33 additions & 16 deletions pa10_hardware_interface/launch/pa10_controller_spawner.launch
Original file line number Diff line number Diff line change
@@ -1,31 +1,48 @@
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<!--<rosparam file="$(find pa10_hardware_interface)/config/joint_names.yaml" command="load"/> -->
<!--<rosparam file="$(find pa10_hardware_interface)/config/pids.yaml" command="load"/>-->
<rosparam file="$(find pa10_hardware_interface)/config/real_controllers.yaml" command="load"/>



<!-- If multiple robots set multiple=true and define the namespace -->
<arg name="robot_name" default="pa10"/>
<arg name="multiple" default="true"/>
<arg name="multi" value="multiple:=$(arg multiple) namespace:=$(arg robot_name)"/>

<!-- The semantic description that corresponds to the URDF -->
<param name="robot_description_semantic" textfile="$(find pa10_moveit_config)/config/pa10.srdf" />
<rosparam command="load" file="$(find pa10_moveit_config)/config/kinematics.yaml"/>
<param name="/$(arg robot_name)/robot_description_semantic" textfile="$(find pa10_moveit_config)/config/pa10.srdf" />
<rosparam command="load" file="$(find pa10_moveit_config)/config/kinematics.yaml" ns="/$(arg robot_name)"/>

<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find pa10_description)/urdf/pa10_csl.urdf.xacro'"/>
<!-- load the controllers -->
<rosparam file="$(find pa10_hardware_interface)/config/real_controllers.yaml" command="load" ns="/$(arg robot_name)"/>

<param name="/$(arg robot_name)/robot_description" command="$(find xacro)/xacro --inorder '$(find pa10_description)/urdf/pa10_csl.urdf.xacro' $(arg multi)"/>

<node name="pa10_hardware_interface" pkg="pa10_hardware_interface" type="pa10_hardware_interface_node" output="screen"/>
<!-- load the controllers -->
<node name="pa10_hardware_interface" pkg="pa10_hardware_interface" type="pa10_hardware_interface_node" ns="/$(arg robot_name)"/>

<node name="pa10_trajectory_controller" pkg="controller_manager" type="spawner" respawn="false"
output="screen" args="
--namespace=/$(arg robot_name)
joint_state_controller
arm_controller
gripper_controller "/>

<node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher"/>
<!-- Publish joint states for all the joints -->

<node pkg="tf" type="static_transform_publisher" name="$(arg robot_name)_bc" args="0.0 0.0 0.0 0.0 0.0 0.0 /world $(arg robot_name)/world 100"/>

<!-- Robot state publisher -->
<node pkg="robot_state_publisher" type="state_publisher" name="$(arg robot_name)_state_publisher">
<param name="publish_frequency" type="double" value="50.0"/>
<param name="tf_prefix" type="string" value="$(arg robot_name)"/>
<remap from="robot_description" to="$(arg robot_name)/robot_description" />
<remap from="joint_states" to="$(arg robot_name)/joint_states" />
</node>

<!--<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher">
<rosparam param="/source_list">[/joint_states]</rosparam>
<param name="use_gui" value="false"/>
</node>-->
<!-- Use MoveIt -->
<group ns="$(arg robot_name)">
<!-- Launch MoveIt -->
<include file="$(find pa10_moveit_config)/launch/pa10_moveit.launch">
<arg name="rviz" value="true" />
<arg name="camera" value="false"/>
</include>
</group>

</launch>

3 changes: 2 additions & 1 deletion pa10_hardware_interface/scripts/pa10_hardware_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -139,7 +139,8 @@ class pa10 : public hardware_interface::RobotHW
host_info.ai_family = AF_UNSPEC; // IP version not specified. Can be both.
host_info.ai_socktype = SOCK_STREAM; // Use SOCK_STREAM for TCP or SOCK_DGRAM for UDP.

status = getaddrinfo("147.102.51.71", "4534", &host_info, &host_info_list);
//status = getaddrinfo("147.102.51.71", "4534", &host_info, &host_info_list);
status = getaddrinfo("192.168.1.71", "4534", &host_info, &host_info_list);

if (status != 0){
std::cout << "getaddrinfo error" << gai_strerror(status) ;
Expand Down
Loading

0 comments on commit 4c8bc35

Please sign in to comment.