|
From: <mm...@us...> - 2008-08-15 01:33:09
|
Revision: 3116
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=3116&view=rev
Author: mmwise
Date: 2008-08-15 01:33:18 +0000 (Fri, 15 Aug 2008)
Log Message:
-----------
cleaning up init mess
Modified Paths:
--------------
pkg/trunk/controllers/pr2_controllers/include/pr2_controllers/laser_scanner_controller.h
pkg/trunk/controllers/pr2_controllers/src/laser_scanner_controller.cpp
pkg/trunk/hardware_test/motors/xml/WG_3021.xml
pkg/trunk/mechanism/mechanism_control/include/mechanism_control/mechanism_control.h
pkg/trunk/mechanism/mechanism_control/manifest.xml
pkg/trunk/mechanism/mechanism_control/src/mechanism_control.cpp
pkg/trunk/mechanism/mechanism_model/src/simple_transmission.cpp
Modified: pkg/trunk/controllers/pr2_controllers/include/pr2_controllers/laser_scanner_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_controllers/include/pr2_controllers/laser_scanner_controller.h 2008-08-15 01:16:40 UTC (rev 3115)
+++ pkg/trunk/controllers/pr2_controllers/include/pr2_controllers/laser_scanner_controller.h 2008-08-15 01:33:18 UTC (rev 3116)
@@ -70,7 +70,7 @@
* \brief Functional way to initialize limits and gains.
*
*/
- void init(double p_gain, double i_gain, double d_gain, double windup, double time, mechanism::Robot *robot, mechanism::Joint *joint);
+ void init(double p_gain, double i_gain, double d_gain, double windup, double time, std::string name, mechanism::Robot *robot);
void initXml(mechanism::Robot *robot, TiXmlElement *config);
/*!
@@ -88,7 +88,7 @@
/*!
* \brief Read the torque of the motor
*/
- double getActual();
+ double getMeasuredState();
/*!
* \brief Issues commands to the joint. Should be called at regular intervals
Modified: pkg/trunk/controllers/pr2_controllers/src/laser_scanner_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_controllers/src/laser_scanner_controller.cpp 2008-08-15 01:16:40 UTC (rev 3115)
+++ pkg/trunk/controllers/pr2_controllers/src/laser_scanner_controller.cpp 2008-08-15 01:33:18 UTC (rev 3116)
@@ -43,9 +43,11 @@
LaserScannerController::LaserScannerController()
{
- // Initialize PID class
+ robot_ = NULL;
+ joint_ = NULL;
+
command_ = 0;
-
+ last_time_ = 0;
profile_index_ = 0;
profile_length_ = 0;
@@ -63,27 +65,27 @@
}
-void LaserScannerController::init(double p_gain, double i_gain, double d_gain, double windup, double time, mechanism::Robot *robot, mechanism::Joint *joint)
+void LaserScannerController::init(double p_gain, double i_gain, double d_gain, double windup, double time, std::string name, mechanism::Robot *robot)
{
- joint_position_controller_.init( p_gain, i_gain, d_gain, windup, time, robot, joint);
robot_ = robot;
+ joint_ = robot->getJoint(name);
+
+ joint_position_controller_.init( p_gain, i_gain, d_gain, windup, time, name, robot);
command_= 0;
last_time_= time;
- joint_ = joint;
}
void LaserScannerController::initXml(mechanism::Robot *robot, TiXmlElement *config)
{
-
-
TiXmlElement *elt = config->FirstChildElement("joint");
- if (elt) {
+ if (elt)
+ {
// TODO: error check if xml attributes/elements are missing
double p_gain = atof(elt->FirstChildElement("pGain")->GetText());
double i_gain = atof(elt->FirstChildElement("iGain")->GetText());
double d_gain = atof(elt->FirstChildElement("dGain")->GetText());
double windup= atof(elt->FirstChildElement("windup")->GetText());
- init(p_gain, i_gain, d_gain, windup, robot->hw_->current_time_, robot, robot->getJoint(elt->Attribute("name")));
+ init(p_gain, i_gain, d_gain, windup, robot->hw_->current_time_,elt->Attribute("name"), robot);
}
}
@@ -101,7 +103,7 @@
}
// Return the measured joint position
-double LaserScannerController::getActual()
+double LaserScannerController::getMeasuredState()
{
return joint_->position_;
}
Modified: pkg/trunk/hardware_test/motors/xml/WG_3021.xml
===================================================================
--- pkg/trunk/hardware_test/motors/xml/WG_3021.xml 2008-08-15 01:16:40 UTC (rev 3115)
+++ pkg/trunk/hardware_test/motors/xml/WG_3021.xml 2008-08-15 01:33:18 UTC (rev 3116)
@@ -18,12 +18,11 @@
<pulsesPerRevolution>1200</pulsesPerRevolution>
</transmission>
- <controller name="test_controller" type="JointVelocityControllerNode">
+ <controller name="test_controller" type="RampInputController">
<joint name="test_joint">
- <pGain>0.0006</pGain>
- <iGain>0.01</iGain>
- <dGain>0</dGain>
- <windup>0.007</windup>
+ <start>0.0</start>
+ <end>0.1</end>
+ <duration>4</duration>
</joint>
</controller>
Modified: pkg/trunk/mechanism/mechanism_control/include/mechanism_control/mechanism_control.h
===================================================================
--- pkg/trunk/mechanism/mechanism_control/include/mechanism_control/mechanism_control.h 2008-08-15 01:16:40 UTC (rev 3115)
+++ pkg/trunk/mechanism/mechanism_control/include/mechanism_control/mechanism_control.h 2008-08-15 01:33:18 UTC (rev 3116)
@@ -75,10 +75,6 @@
bool addController(controller::Controller *c, const std::string &name);
bool spawnController(const std::string &type, const std::string &name, TiXmlElement *config);
bool killController(const std::string &name);
- bool spawnController(const std::string &type,
- const std::string &name,
- double p_gain, double i_gain, double d_gain, double windup,
- double time, mechanism::Joint *joint);
bool addJoint(mechanism::Joint* j);
bool addSimpleTransmission(mechanism::SimpleTransmission *st);
controller::Controller* getControllerByName(std::string name);
Modified: pkg/trunk/mechanism/mechanism_control/manifest.xml
===================================================================
--- pkg/trunk/mechanism/mechanism_control/manifest.xml 2008-08-15 01:16:40 UTC (rev 3115)
+++ pkg/trunk/mechanism/mechanism_control/manifest.xml 2008-08-15 01:33:18 UTC (rev 3116)
@@ -10,6 +10,7 @@
<depend package="tinyxml"/>
<depend package="mechanism_model"/>
<depend package="generic_controllers"/>
+<depend package="pr2_controllers"/>
<depend package="misc_utils" />
<depend package="rospy" />
<export>
Modified: pkg/trunk/mechanism/mechanism_control/src/mechanism_control.cpp
===================================================================
--- pkg/trunk/mechanism/mechanism_control/src/mechanism_control.cpp 2008-08-15 01:16:40 UTC (rev 3115)
+++ pkg/trunk/mechanism/mechanism_control/src/mechanism_control.cpp 2008-08-15 01:33:18 UTC (rev 3116)
@@ -203,26 +203,7 @@
return true;
}
-bool MechanismControl::spawnController(const std::string &type,
- const std::string &name,
- double p_gain, double i_gain, double d_gain, double windup,
- double time, mechanism::Joint *joint)
-{
- controller::Controller *c = controller::ControllerFactory::instance().create(type);
- if (c == NULL)
- return false;
- //c->init(p_gain,i_gain,d_gain,windup,time,&model_,joint);
- if (!addController(c, name))
- {
- delete c;
- return false;
- }
-
- return true;
-}
-
-
bool MechanismControl::spawnController(const std::string &type,
const std::string &name,
TiXmlElement *config)
@@ -230,6 +211,7 @@
controller::Controller *c = controller::ControllerFactory::instance().create(type);
if (c == NULL)
return false;
+ printf("Spawning %s: %08x\n", name.c_str(), &model_);
c->initXml(&model_, config);
if (!addController(c, name))
Modified: pkg/trunk/mechanism/mechanism_model/src/simple_transmission.cpp
===================================================================
--- pkg/trunk/mechanism/mechanism_model/src/simple_transmission.cpp 2008-08-15 01:16:40 UTC (rev 3115)
+++ pkg/trunk/mechanism/mechanism_model/src/simple_transmission.cpp 2008-08-15 01:33:18 UTC (rev 3116)
@@ -76,6 +76,7 @@
joint_->position_ = ((double)actuator_->state_.encoder_count_*2*M_PI)/(pulses_per_revolution_ * mechanical_reduction_);
joint_->velocity_ = ((double)actuator_->state_.encoder_velocity_*2*M_PI)/(pulses_per_revolution_ * mechanical_reduction_);
joint_->applied_effort_ = actuator_->state_.last_measured_current_ * (motor_torque_constant_ * mechanical_reduction_);
+
}
void SimpleTransmission::propagatePositionBackwards()
@@ -89,9 +90,11 @@
{
actuator_->command_.current_ = joint_->commanded_effort_/(motor_torque_constant_ * mechanical_reduction_);
actuator_->command_.enable_ = true;
+
}
void SimpleTransmission::propagateEffortBackwards()
{
joint_->commanded_effort_ = actuator_->command_.current_ * motor_torque_constant_ * mechanical_reduction_;
+
}
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|