Skip to content

Commit eb8bb7f

Browse files
authored
Merge pull request #175 from liyixin135/master
Initialize odom2pitch_des in rate through starting
2 parents 5a71357 + dc4e9f4 commit eb8bb7f

File tree

2 files changed

+10
-13
lines changed

2 files changed

+10
-13
lines changed

rm_gimbal_controllers/include/rm_gimbal_controllers/gimbal_base.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -204,6 +204,7 @@ class Controller : public controller_interface::MultiInterfaceController<rm_cont
204204
TRAJ
205205
};
206206
int state_ = RATE;
207+
bool start_ = false;
207208
};
208209

209210
} // namespace rm_gimbal_controllers

rm_gimbal_controllers/src/gimbal_base.cpp

Lines changed: 9 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -148,22 +148,11 @@ bool Controller::init(hardware_interface::RobotHW* robot_hw, ros::NodeHandle& ro
148148
return true;
149149
}
150150

151-
void Controller::starting(const ros::Time& time)
151+
void Controller::starting(const ros::Time& /*unused*/)
152152
{
153153
state_ = RATE;
154154
state_changed_ = true;
155-
try
156-
{
157-
odom2pitch_ = robot_state_handle_.lookupTransform("odom", pitch_joint_urdf_->child_link_name, time);
158-
}
159-
catch (tf2::TransformException& ex)
160-
{
161-
ROS_WARN("%s", ex.what());
162-
return;
163-
}
164-
odom2gimbal_des_.transform.rotation = odom2pitch_.transform.rotation;
165-
odom2gimbal_des_.header.stamp = time;
166-
robot_state_handle_.setTransform(odom2gimbal_des_, "rm_gimbal_controllers");
155+
start_ = true;
167156
}
168157

169158
void Controller::update(const ros::Time& time, const ros::Duration& period)
@@ -266,6 +255,13 @@ void Controller::rate(const ros::Time& time, const ros::Duration& period)
266255
{ // on enter
267256
state_changed_ = false;
268257
ROS_INFO("[Gimbal] Enter RATE");
258+
if (start_)
259+
{
260+
odom2gimbal_des_.transform.rotation = odom2pitch_.transform.rotation;
261+
odom2gimbal_des_.header.stamp = time;
262+
robot_state_handle_.setTransform(odom2gimbal_des_, "rm_gimbal_controllers");
263+
start_ = false;
264+
}
269265
}
270266
else
271267
{

0 commit comments

Comments
 (0)