Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #include "ethercat_trigger_controllers/projector_controller.h"
00036 #include "ros/console.h"
00037 #include "pluginlib/class_list_macros.h"
00038
00039 PLUGINLIB_EXPORT_CLASS( controller::ProjectorController, pr2_controller_interface::Controller)
00040
00041 using std::string;
00042 using namespace controller;
00043
00044 ProjectorController::ProjectorController()
00045 {
00046 ROS_DEBUG("creating controller...");
00047 }
00048
00049 ProjectorController::~ProjectorController()
00050 {
00051 }
00052
00053 void ProjectorController::update()
00054 {
00056 uint32_t rising = projector_->state_.rising_timestamp_us_;
00057 uint32_t falling = projector_->state_.falling_timestamp_us_;
00058 double curtime = robot_->getTime().toSec();
00059 double delta = curtime - start_time_;
00060 delta -= fmod(delta, 0.001);
00061
00062 projector_->command_.current_ = current_setting_;
00063
00064 if (falling != old_falling_)
00065 {
00066 old_falling_ = falling;
00067 if (falling_edge_pub_ && falling_edge_pub_->trylock())
00068 {
00069
00070
00071 falling_edge_pub_->msg_.stamp = ros::Time(delta);
00072 falling_edge_pub_->unlockAndPublish();
00073 }
00074 }
00075 if (rising != old_rising_)
00076 {
00077 old_rising_ = rising;
00078 if (rising_edge_pub_ && rising_edge_pub_->trylock())
00079 {
00080
00081
00082 rising_edge_pub_->msg_.stamp = ros::Time(delta);
00083 rising_edge_pub_->unlockAndPublish();
00084 }
00085 }
00086 }
00087
00088 void ProjectorController::starting()
00089 {
00090 projector_->command_.enable_ = true;
00091 projector_->command_.pulse_replicator_ = false;
00092
00093 old_rising_ = projector_->state_.rising_timestamp_us_;
00094 old_falling_ = projector_->state_.falling_timestamp_us_;
00095 start_time_ = 0;
00096 }
00097
00098 void ProjectorController::stopping()
00099 {
00100 projector_->command_.enable_ = false;
00101 projector_->command_.pulse_replicator_ = true;
00102
00103 projector_->command_.current_ = 0;
00104 }
00105
00106 bool ProjectorController::init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle& n)
00107 {
00108 node_handle_ = n;
00109
00110 assert(robot);
00111 robot_=robot;
00112
00113 ROS_DEBUG("ProjectorController::init starting");
00114
00115
00116
00117 if (!n.getParam("actuator", actuator_name_)){
00118 ROS_ERROR("ProjectorController was not given an actuator.");
00119 return false;
00120 }
00121
00122 rising_edge_pub_.reset(new realtime_tools::RealtimePublisher<std_msgs::Header>(n, "rising_edge_timestamps", 10));
00123 falling_edge_pub_.reset(new realtime_tools::RealtimePublisher<std_msgs::Header>(n, "falling_edge_timestamps", 10));
00124
00125 projector_ = robot_->model_->hw_->getProjector(actuator_name_);
00126 ROS_DEBUG("Got projector: %p\n", projector_);
00127 if (!projector_)
00128 {
00129 ROS_ERROR("ProjectorController could not find digital out named \"%s\".",
00130 actuator_name_.c_str());
00131 return false;
00132 }
00133
00134 n.param("current", current_setting_, 27.0);
00135 ROS_DEBUG("Projector current = %f", current_setting_);
00136
00137 return true;
00138 }