added comments

This commit is contained in:
Kayman 2018-05-03 16:05:02 +09:00
parent f9e2bded67
commit 2f3311d5ea
2 changed files with 18 additions and 16 deletions

View File

@ -1,24 +1,24 @@
<?xml version="1.0" ?>
<launch>
<param name="gazebo" value="false" type="bool"/>
<param name="gazebo_robot_name" value="robotis_op3"/>
<param name="gazebo" value="false" type="bool"/>
<param name="gazebo_robot_name" value="robotis_op3"/>
<param name="offset_file_path" value="$(find op3_manager)/config/offset.yaml"/>
<param name="robot_file_path" value="$(find op3_manager)/config/OP3.robot"/>
<param name="init_file_path" value="$(find op3_manager)/config/dxl_init_OP3.yaml"/>
<param name="device_name" value="/dev/ttyUSB0"/>
<param name="offset_file_path" value="$(find op3_manager)/config/offset.yaml"/>
<param name="robot_file_path" value="$(find op3_manager)/config/OP3.robot"/>
<param name="init_file_path" value="$(find op3_manager)/config/dxl_init_OP3.yaml"/>
<param name="device_name" value="/dev/ttyUSB0"/>
<param name="/robotis/direct_control/default_moving_time" value="0.04"/>
<param name="/robotis/direct_control/default_moving_angle" value="90"/>
<param name="/robotis/direct_control/default_moving_time" value="0.04"/>
<param name="/robotis/direct_control/default_moving_angle" value="90"/>
<!-- OP3 Manager -->
<node pkg="op3_manager" type="op3_manager" name="op3_manager" output="screen">
<param name="angle_unit" value="30" />
</node>
<!-- OP3 Manager -->
<node pkg="op3_manager" type="op3_manager" name="op3_manager" output="screen">
<param name="angle_unit" value="30" />
</node>
<!-- OP3 Localization -->
<node pkg="op3_localization" type="op3_localization" name="op3_localization" output="screen"/>
<!-- OP3 Localization -->
<node pkg="op3_localization" type="op3_localization" name="op3_localization" output="screen"/>
<!-- OP3 Read-Write demo -->
<node pkg="op3_read_write_demo" type="read_write" name="op3_read_write" output="screen"/>
<!-- OP3 Read-Write demo -->
<node pkg="op3_read_write_demo" type="read_write" name="op3_read_write" output="screen"/>
</launch>

View File

@ -150,6 +150,7 @@ void jointstatesCallback(const sensor_msgs::JointState::ConstPtr& msg)
std::string joint_name = msg->name[ix];
double joint_position = msg->position[ix];
// mirror and copy joint angles from right to left
if(joint_name == "r_sho_pitch")
{
write_msg.name.push_back("r_sho_pitch");
@ -173,6 +174,7 @@ void jointstatesCallback(const sensor_msgs::JointState::ConstPtr& msg)
}
}
// publish a message to set the joint angles
if(control_module == Framework)
write_joint_pub.publish(write_msg);
else if(control_module == DirectControlModule)