|
From: <hsu...@us...> - 2008-08-12 00:54:14
|
Revision: 2938
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=2938&view=rev
Author: hsujohnhsu
Date: 2008-08-12 00:54:23 +0000 (Tue, 12 Aug 2008)
Log Message:
-----------
update to fix gripper control.
Modified Paths:
--------------
pkg/trunk/drivers/simulator/gazebo_plugin/src/test_actuators.cpp
pkg/trunk/robot_descriptions/wg_robot_description/pr2/transmission_test.xml
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/test_actuators.cpp
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/test_actuators.cpp 2008-08-12 00:53:14 UTC (rev 2937)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/test_actuators.cpp 2008-08-12 00:54:23 UTC (rev 2938)
@@ -697,14 +697,29 @@
}
}
- if (false)
+ // -------------------------------------------------------------------------------------------------
+ // - -
+ // - test some controllers set points by hardcode for debug -
+ // - -
+ // -------------------------------------------------------------------------------------------------
+ if (true)
for (std::vector<Robot_controller_>::iterator rci = robot_controllers_.begin(); rci != robot_controllers_.end() ; rci++)
- if ((*rci).control_mode == "PD_CONTROL")
- (*rci).pcontroller.setCommand(-0.3);
- else if ((*rci).control_mode == "VELOCITY_CONTROL")
- (*rci).vcontroller.setCommand(1.0);
+ {
+ if (false)
+ if ((*rci).control_mode == "PD_CONTROL")
+ (*rci).pcontroller.setCommand(-0.3);
+ else if ((*rci).control_mode == "VELOCITY_CONTROL")
+ (*rci).vcontroller.setCommand(1.0);
+ if (true)
+ if ((*rci).gazebo_joint_type == "gripper")
+ (*rci).pcontroller.setCommand(0.2);
+ }
- // update each controller, this updates the joint that the controller was initialized with
+ // -------------------------------------------------------------------------------------------------
+ // - -
+ // - update each controller, this updates the joint that the controller was initialized with -
+ // - -
+ // -------------------------------------------------------------------------------------------------
for (std::vector<Robot_controller_>::iterator rci = robot_controllers_.begin(); rci != robot_controllers_.end() ; rci++)
{
try
@@ -725,7 +740,11 @@
}
}
- // update actuators from robot joints via forward transmission propagation
+ // -------------------------------------------------------------------------------------------------
+ // - -
+ // - update actuators from robot joints via forward transmission propagation -
+ // - -
+ // -------------------------------------------------------------------------------------------------
for (std::vector<Robot_transmission_>::iterator rti = robot_transmissions_.begin(); rti != robot_transmissions_.end(); rti++)
{
// assign actuator states
@@ -738,7 +757,11 @@
// below is when the actuator stuff goes to the hardware
//============================================================================================
- // reverse transmission, get joint data from actuators
+ // -------------------------------------------------------------------------------------------------
+ // - -
+ // - reverse transmission, get joint data from actuators -
+ // - -
+ // -------------------------------------------------------------------------------------------------
for (std::vector<Robot_transmission_>::iterator rrti = reverse_robot_transmissions_.begin(); rrti != reverse_robot_transmissions_.end(); rrti++)
{
// assign joint states
@@ -747,7 +770,11 @@
(*rrti).simple_transmission.propagateEffortBackwards();
}
- // udpate gazebo joint for this controller joint
+ // -------------------------------------------------------------------------------------------------
+ // - -
+ // - udpate gazebo joint for this controller joint -
+ // - -
+ // -------------------------------------------------------------------------------------------------
for (std::vector<Robot_controller_>::iterator rci = robot_controllers_.begin(); rci != robot_controllers_.end() ; rci++)
{
if ((*rci).gazebo_joint_type == "gripper")
@@ -765,6 +792,13 @@
gj_f_r->SetTorque( -(*rci).reverse_mech_joint_->commanded_effort_ - damp_force_f_r );
gj_f_tip_l->SetTorque(-(*rci).reverse_mech_joint_->commanded_effort_ - damp_force_f_tip_l);
gj_f_tip_r->SetTorque( (*rci).reverse_mech_joint_->commanded_effort_ - damp_force_f_tip_r);
+
+ // std::cout << " updating gripper ----------------------------- " << std::endl;
+ // std::cout << " f_l " << (*rci).reverse_mech_joint_->commanded_effort_ << " " << damp_force_f_l << std::endl;
+ // std::cout << " f_r " << -(*rci).reverse_mech_joint_->commanded_effort_ << " " << damp_force_f_r << std::endl;
+ // std::cout << " ftl " << -(*rci).reverse_mech_joint_->commanded_effort_ << " " << damp_force_f_tip_l<< std::endl;
+ // std::cout << " ftr " << (*rci).reverse_mech_joint_->commanded_effort_ << " " << damp_force_f_tip_r<< std::endl;
+
}
else if ((*rci).gazebo_joint_type == "slider")
{
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2/transmission_test.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2/transmission_test.xml 2008-08-12 00:53:14 UTC (rev 2937)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2/transmission_test.xml 2008-08-12 00:54:23 UTC (rev 2938)
@@ -151,34 +151,13 @@
</transmission>
<!-- fingers share a single motor -->
- <transmission type="SimpleTransmission" name="finger_l_left_trans">
+ <transmission type="SimpleTransmission" name="gripper_left_trans">
<actuator name="gripper_left_motor" />
- <joint name="finger_l_left_joint" />
+ <joint name="gripper_left_joint" />
<mechanicalReduction>1</mechanicalReduction>
<motorTorqueConstant>1</motorTorqueConstant>
<pulsesPerRevolution>90000</pulsesPerRevolution>
</transmission>
- <transmission type="SimpleTransmission" name="finger_r_left_trans">
- <actuator name="gripper_left_motor" />
- <joint name="finger_r_left_joint" />
- <mechanicalReduction>-1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
- <transmission type="SimpleTransmission" name="finger_tip_l_left_trans">
- <actuator name="gripper_left_motor" />
- <joint name="finger_tip_l_left_joint" />
- <mechanicalReduction>-1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
- <transmission type="SimpleTransmission" name="finger_tip_r_left_trans">
- <actuator name="gripper_left_motor" />
- <joint name="finger_tip_r_left_joint" />
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
<!-- ========================================= -->
<!-- Right Arm -->
<transmission type="SimpleTransmission" name="shoulder_pan_right_trans">
@@ -239,34 +218,13 @@
</transmission>
<!-- fingers share a single motor -->
- <transmission type="SimpleTransmission" name="finger_l_right_trans">
+ <transmission type="SimpleTransmission" name="gripper_right_trans">
<actuator name="gripper_right_motor" />
- <joint name="finger_l_right_joint" />
+ <joint name="gripper_right_joint" />
<mechanicalReduction>1</mechanicalReduction>
<motorTorqueConstant>1</motorTorqueConstant>
<pulsesPerRevolution>90000</pulsesPerRevolution>
</transmission>
- <transmission type="SimpleTransmission" name="finger_r_right_trans">
- <actuator name="gripper_right_motor" />
- <joint name="finger_r_right_joint" />
- <mechanicalReduction>-1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
- <transmission type="SimpleTransmission" name="finger_tip_l_right_trans">
- <actuator name="gripper_right_motor" />
- <joint name="finger_tip_l_right_joint" />
- <mechanicalReduction>-1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
- <transmission type="SimpleTransmission" name="finger_tip_r_right_trans">
- <actuator name="gripper_right_motor" />
- <joint name="finger_tip_r_right_joint" />
- <mechanicalReduction>1</mechanicalReduction>
- <motorTorqueConstant>1</motorTorqueConstant>
- <pulsesPerRevolution>90000</pulsesPerRevolution>
- </transmission>
<!-- ========================================= -->
<!-- Head -->
<transmission type="SimpleTransmission" name="head_pan_trans">
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|